CTRE Phoenix 6 C++ 26.0.0-beta-1
Loading...
Searching...
No Matches
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
13
18
20#include <units/acceleration.h>
21#include <units/angle.h>
22#include <units/angular_velocity.h>
23#include <units/dimensionless.h>
24#include <units/magnetic_field_strength.h>
25#include <units/temperature.h>
26#include <units/time.h>
27#include <units/voltage.h>
28
29namespace ctre {
30namespace phoenix6 {
31
32namespace hardware {
33namespace core {
34 class CorePigeon2;
35}
36}
37
38namespace configs {
39
40/**
41 * Class description for the Pigeon 2 IMU sensor that measures orientation.
42 *
43 * This defines all configurations for the hardware#Pigeon2.
44 */
46{
47public:
48 constexpr Pigeon2Configuration() = default;
49
50 /**
51 * \brief True if we should factory default newer unsupported configs,
52 * false to leave newer unsupported configs alone.
53 *
54 * \details This flag addresses a corner case where the device may have
55 * firmware with newer configs that didn't exist when this
56 * version of the API was built. If this occurs and this
57 * flag is true, unsupported new configs will be factory
58 * defaulted to avoid unexpected behavior.
59 *
60 * This is also the behavior in Phoenix 5, so this flag
61 * is defaulted to true to match.
62 */
64
65
66 /**
67 * \brief Configs for Pigeon 2's Mount Pose configuration.
68 *
69 * \details These configs allow the Pigeon2 to be mounted in whatever
70 * orientation that's desired and ensure the reported
71 * Yaw/Pitch/Roll is from the robot's reference.
72 *
73 * Parameter list:
74 *
75 * - MountPoseConfigs#MountPoseYaw
76 * - MountPoseConfigs#MountPosePitch
77 * - MountPoseConfigs#MountPoseRoll
78 *
79 */
81
82 /**
83 * \brief Configs to trim the Pigeon2's gyroscope.
84 *
85 * \details Pigeon2 allows the user to trim the gyroscope's
86 * sensitivity. While this isn't necessary for the Pigeon2,
87 * as it comes calibrated out-of-the-box, users can make use
88 * of this to make the Pigeon2 even more accurate for their
89 * application.
90 *
91 * Parameter list:
92 *
93 * - GyroTrimConfigs#GyroScalarX
94 * - GyroTrimConfigs#GyroScalarY
95 * - GyroTrimConfigs#GyroScalarZ
96 *
97 */
99
100 /**
101 * \brief Configs to enable/disable various features of the Pigeon2.
102 *
103 * \details These configs allow the user to enable or disable various
104 * aspects of the Pigeon2.
105 *
106 * Parameter list:
107 *
108 * - Pigeon2FeaturesConfigs#EnableCompass
109 * - Pigeon2FeaturesConfigs#DisableTemperatureCompensation
110 * - Pigeon2FeaturesConfigs#DisableNoMotionCalibration
111 *
112 */
114
115 /**
116 * \brief Custom Params.
117 *
118 * \details Custom paramaters that have no real impact on controller.
119 *
120 * Parameter list:
121 *
122 * - CustomParamsConfigs#CustomParam0
123 * - CustomParamsConfigs#CustomParam1
124 *
125 */
127
128 /**
129 * \brief Modifies this configuration's MountPose parameter and returns itself for
130 * method-chaining and easier to use config API.
131 *
132 * Configs for Pigeon 2's Mount Pose configuration.
133 *
134 * \details These configs allow the Pigeon2 to be mounted in whatever
135 * orientation that's desired and ensure the reported
136 * Yaw/Pitch/Roll is from the robot's reference.
137 *
138 * Parameter list:
139 *
140 * - MountPoseConfigs#MountPoseYaw
141 * - MountPoseConfigs#MountPosePitch
142 * - MountPoseConfigs#MountPoseRoll
143 *
144 *
145 * \param newMountPose Parameter to modify
146 * \returns Itself
147 */
149 {
150 MountPose = std::move(newMountPose);
151 return *this;
152 }
153
154 /**
155 * \brief Modifies this configuration's GyroTrim parameter and returns itself for
156 * method-chaining and easier to use config API.
157 *
158 * Configs to trim the Pigeon2's gyroscope.
159 *
160 * \details Pigeon2 allows the user to trim the gyroscope's
161 * sensitivity. While this isn't necessary for the Pigeon2,
162 * as it comes calibrated out-of-the-box, users can make use
163 * of this to make the Pigeon2 even more accurate for their
164 * application.
165 *
166 * Parameter list:
167 *
168 * - GyroTrimConfigs#GyroScalarX
169 * - GyroTrimConfigs#GyroScalarY
170 * - GyroTrimConfigs#GyroScalarZ
171 *
172 *
173 * \param newGyroTrim Parameter to modify
174 * \returns Itself
175 */
177 {
178 GyroTrim = std::move(newGyroTrim);
179 return *this;
180 }
181
182 /**
183 * \brief Modifies this configuration's Pigeon2Features parameter and returns itself for
184 * method-chaining and easier to use config API.
185 *
186 * Configs to enable/disable various features of the Pigeon2.
187 *
188 * \details These configs allow the user to enable or disable various
189 * aspects of the Pigeon2.
190 *
191 * Parameter list:
192 *
193 * - Pigeon2FeaturesConfigs#EnableCompass
194 * - Pigeon2FeaturesConfigs#DisableTemperatureCompensation
195 * - Pigeon2FeaturesConfigs#DisableNoMotionCalibration
196 *
197 *
198 * \param newPigeon2Features Parameter to modify
199 * \returns Itself
200 */
202 {
203 Pigeon2Features = std::move(newPigeon2Features);
204 return *this;
205 }
206
207 /**
208 * \brief Modifies this configuration's CustomParams parameter and returns itself for
209 * method-chaining and easier to use config API.
210 *
211 * Custom Params.
212 *
213 * \details Custom paramaters that have no real impact on controller.
214 *
215 * Parameter list:
216 *
217 * - CustomParamsConfigs#CustomParam0
218 * - CustomParamsConfigs#CustomParam1
219 *
220 *
221 * \param newCustomParams Parameter to modify
222 * \returns Itself
223 */
225 {
226 CustomParams = std::move(newCustomParams);
227 return *this;
228 }
229
230 /**
231 * \brief Get the string representation of this configuration
232 */
233 std::string ToString() const override;
234
235 /**
236 * \brief Get the serialized form of this configuration
237 */
238 std::string Serialize() const final;
239 /**
240 * \brief Take a string and deserialize it to this configuration
241 */
242 ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final;
243};
244
245/**
246 * Class description for the Pigeon 2 IMU sensor that measures orientation.
247 *
248 * This handles applying and refreshing configurations for the hardware#Pigeon2.
249 */
251{
252private:
254 ParentConfigurator{std::move(id)}
255 {}
256
258
259public:
260 /**
261 * \brief Refreshes the values of the specified config group.
262 *
263 * This will wait up to #DefaultTimeoutSeconds.
264 *
265 * \details Call to refresh the selected configs from the device.
266 *
267 * \param configs The configs to refresh
268 * \returns StatusCode of refreshing the configs
269 */
271 {
272 return Refresh(configs, DefaultTimeoutSeconds);
273 }
274
275 /**
276 * \brief Refreshes the values of the specified config group.
277 *
278 * \details Call to refresh the selected configs from the device.
279 *
280 * \param configs The configs to refresh
281 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
282 * \returns StatusCode of refreshing the configs
283 */
284 ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, units::time::second_t timeoutSeconds) const
285 {
286 std::string ref;
287 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
288 configs.Deserialize(ref);
289 return ret;
290 }
291
292 /**
293 * \brief Applies the contents of the specified config to the device.
294 *
295 * This will wait up to #DefaultTimeoutSeconds.
296 *
297 * \details Call to apply the selected configs.
298 *
299 * \param configs Configs to apply against.
300 * \returns StatusCode of the set command
301 */
303 {
304 return Apply(configs, DefaultTimeoutSeconds);
305 }
306
307 /**
308 * \brief Applies the contents of the specified config to the device.
309 *
310 * \details Call to apply the selected configs.
311 *
312 * \param configs Configs to apply against.
313 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
314 * \returns StatusCode of the set command
315 */
316 ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs, units::time::second_t timeoutSeconds)
317 {
318 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, configs.FutureProofConfigs, false);
319 }
320
321
322 /**
323 * \brief Refreshes the values of the specified config group.
324 *
325 * This will wait up to #DefaultTimeoutSeconds.
326 *
327 * \details Call to refresh the selected configs from the device.
328 *
329 * \param configs The configs to refresh
330 * \returns StatusCode of refreshing the configs
331 */
333 {
334 return Refresh(configs, DefaultTimeoutSeconds);
335 }
336 /**
337 * \brief Refreshes the values of the specified config group.
338 *
339 * \details Call to refresh the selected configs from the device.
340 *
341 * \param configs The configs to refresh
342 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
343 * \returns StatusCode of refreshing the configs
344 */
345 ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, units::time::second_t timeoutSeconds) const
346 {
347 std::string ref;
348 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
349 configs.Deserialize(ref);
350 return ret;
351 }
352
353 /**
354 * \brief Applies the contents of the specified config to the device.
355 *
356 * This will wait up to #DefaultTimeoutSeconds.
357 *
358 * \details Call to apply the selected configs.
359 *
360 * \param configs Configs to apply against.
361 * \returns StatusCode of the set command
362 */
364 {
365 return Apply(configs, DefaultTimeoutSeconds);
366 }
367
368 /**
369 * \brief Applies the contents of the specified config to the device.
370 *
371 * \details Call to apply the selected configs.
372 *
373 * \param configs Configs to apply against.
374 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
375 * \returns StatusCode of the set command
376 */
377 ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs, units::time::second_t timeoutSeconds)
378 {
379 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
380 }
381
382 /**
383 * \brief Refreshes the values of the specified config group.
384 *
385 * This will wait up to #DefaultTimeoutSeconds.
386 *
387 * \details Call to refresh the selected configs from the device.
388 *
389 * \param configs The configs to refresh
390 * \returns StatusCode of refreshing the configs
391 */
393 {
394 return Refresh(configs, DefaultTimeoutSeconds);
395 }
396 /**
397 * \brief Refreshes the values of the specified config group.
398 *
399 * \details Call to refresh the selected configs from the device.
400 *
401 * \param configs The configs to refresh
402 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
403 * \returns StatusCode of refreshing the configs
404 */
405 ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, units::time::second_t timeoutSeconds) const
406 {
407 std::string ref;
408 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
409 configs.Deserialize(ref);
410 return ret;
411 }
412
413 /**
414 * \brief Applies the contents of the specified config to the device.
415 *
416 * This will wait up to #DefaultTimeoutSeconds.
417 *
418 * \details Call to apply the selected configs.
419 *
420 * \param configs Configs to apply against.
421 * \returns StatusCode of the set command
422 */
424 {
425 return Apply(configs, DefaultTimeoutSeconds);
426 }
427
428 /**
429 * \brief Applies the contents of the specified config to the device.
430 *
431 * \details Call to apply the selected configs.
432 *
433 * \param configs Configs to apply against.
434 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
435 * \returns StatusCode of the set command
436 */
437 ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs, units::time::second_t timeoutSeconds)
438 {
439 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
440 }
441
442 /**
443 * \brief Refreshes the values of the specified config group.
444 *
445 * This will wait up to #DefaultTimeoutSeconds.
446 *
447 * \details Call to refresh the selected configs from the device.
448 *
449 * \param configs The configs to refresh
450 * \returns StatusCode of refreshing the configs
451 */
453 {
454 return Refresh(configs, DefaultTimeoutSeconds);
455 }
456 /**
457 * \brief Refreshes the values of the specified config group.
458 *
459 * \details Call to refresh the selected configs from the device.
460 *
461 * \param configs The configs to refresh
462 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
463 * \returns StatusCode of refreshing the configs
464 */
465 ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds) const
466 {
467 std::string ref;
468 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
469 configs.Deserialize(ref);
470 return ret;
471 }
472
473 /**
474 * \brief Applies the contents of the specified config to the device.
475 *
476 * This will wait up to #DefaultTimeoutSeconds.
477 *
478 * \details Call to apply the selected configs.
479 *
480 * \param configs Configs to apply against.
481 * \returns StatusCode of the set command
482 */
484 {
485 return Apply(configs, DefaultTimeoutSeconds);
486 }
487
488 /**
489 * \brief Applies the contents of the specified config to the device.
490 *
491 * \details Call to apply the selected configs.
492 *
493 * \param configs Configs to apply against.
494 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
495 * \returns StatusCode of the set command
496 */
497 ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds)
498 {
499 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
500 }
501
502 /**
503 * \brief Refreshes the values of the specified config group.
504 *
505 * This will wait up to #DefaultTimeoutSeconds.
506 *
507 * \details Call to refresh the selected configs from the device.
508 *
509 * \param configs The configs to refresh
510 * \returns StatusCode of refreshing the configs
511 */
513 {
514 return Refresh(configs, DefaultTimeoutSeconds);
515 }
516 /**
517 * \brief Refreshes the values of the specified config group.
518 *
519 * \details Call to refresh the selected configs from the device.
520 *
521 * \param configs The configs to refresh
522 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
523 * \returns StatusCode of refreshing the configs
524 */
525 ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs, units::time::second_t timeoutSeconds) const
526 {
527 std::string ref;
528 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
529 configs.Deserialize(ref);
530 return ret;
531 }
532
533 /**
534 * \brief Applies the contents of the specified config to the device.
535 *
536 * This will wait up to #DefaultTimeoutSeconds.
537 *
538 * \details Call to apply the selected configs.
539 *
540 * \param configs Configs to apply against.
541 * \returns StatusCode of the set command
542 */
544 {
545 return Apply(configs, DefaultTimeoutSeconds);
546 }
547
548 /**
549 * \brief Applies the contents of the specified config to the device.
550 *
551 * \details Call to apply the selected configs.
552 *
553 * \param configs Configs to apply against.
554 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
555 * \returns StatusCode of the set command
556 */
557 ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs, units::time::second_t timeoutSeconds)
558 {
559 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
560 }
561
562
563 /**
564 * \brief The yaw to set the Pigeon2 to right now.
565 *
566 * This will wait up to #DefaultTimeoutSeconds.
567 *
568 * This is available in the configurator in case the user wants
569 * to initialize their device entirely without passing a device
570 * reference down to the code that performs the initialization.
571 * In this case, the user passes down the configurator object
572 * and performs all the initialization code on the object.
573 *
574 * \param newValue Value to set to. Units are in deg.
575 * \returns StatusCode of the set command
576 */
577 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
578 {
579 return SetYaw(newValue, DefaultTimeoutSeconds);
580 }
581 /**
582 * \brief The yaw to set the Pigeon2 to right now.
583 *
584 * This is available in the configurator in case the user wants
585 * to initialize their device entirely without passing a device
586 * reference down to the code that performs the initialization.
587 * In this case, the user passes down the configurator object
588 * and performs all the initialization code on the object.
589 *
590 * \param newValue Value to set to. Units are in deg.
591 * \param timeoutSeconds Maximum time to wait up to in seconds.
592 * \returns StatusCode of the set command
593 */
594 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds);
595
596 /**
597 * \brief Clear the sticky faults in the device.
598 *
599 * \details This typically has no impact on the device functionality.
600 * Instead, it just clears telemetry faults that are accessible via
601 * API and Tuner Self-Test.
602 *
603 * This will wait up to #DefaultTimeoutSeconds.
604 *
605 * This is available in the configurator in case the user wants
606 * to initialize their device entirely without passing a device
607 * reference down to the code that performs the initialization.
608 * In this case, the user passes down the configurator object
609 * and performs all the initialization code on the object.
610 *
611 * \returns StatusCode of the set command
612 */
614 {
615 return ClearStickyFaults(DefaultTimeoutSeconds);
616 }
617 /**
618 * \brief Clear the sticky faults in the device.
619 *
620 * \details This typically has no impact on the device functionality.
621 * Instead, it just clears telemetry faults that are accessible via
622 * API and Tuner Self-Test.
623 *
624 * This is available in the configurator in case the user wants
625 * to initialize their device entirely without passing a device
626 * reference down to the code that performs the initialization.
627 * In this case, the user passes down the configurator object
628 * and performs all the initialization code on the object.
629 *
630 * \param timeoutSeconds Maximum time to wait up to in seconds.
631 * \returns StatusCode of the set command
632 */
633 ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds);
634
635 /**
636 * \brief Clear sticky fault: Hardware fault occurred
637 *
638 * This will wait up to #DefaultTimeoutSeconds.
639 *
640 * This is available in the configurator in case the user wants
641 * to initialize their device entirely without passing a device
642 * reference down to the code that performs the initialization.
643 * In this case, the user passes down the configurator object
644 * and performs all the initialization code on the object.
645 *
646 * \returns StatusCode of the set command
647 */
649 {
650 return ClearStickyFault_Hardware(DefaultTimeoutSeconds);
651 }
652 /**
653 * \brief Clear sticky fault: Hardware fault occurred
654 *
655 * This is available in the configurator in case the user wants
656 * to initialize their device entirely without passing a device
657 * reference down to the code that performs the initialization.
658 * In this case, the user passes down the configurator object
659 * and performs all the initialization code on the object.
660 *
661 * \param timeoutSeconds Maximum time to wait up to in seconds.
662 * \returns StatusCode of the set command
663 */
664 ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds);
665
666 /**
667 * \brief Clear sticky fault: Device supply voltage dropped to near
668 * brownout levels
669 *
670 * This will wait up to #DefaultTimeoutSeconds.
671 *
672 * This is available in the configurator in case the user wants
673 * to initialize their device entirely without passing a device
674 * reference down to the code that performs the initialization.
675 * In this case, the user passes down the configurator object
676 * and performs all the initialization code on the object.
677 *
678 * \returns StatusCode of the set command
679 */
681 {
682 return ClearStickyFault_Undervoltage(DefaultTimeoutSeconds);
683 }
684 /**
685 * \brief Clear sticky fault: Device supply voltage dropped to near
686 * brownout levels
687 *
688 * This is available in the configurator in case the user wants
689 * to initialize their device entirely without passing a device
690 * reference down to the code that performs the initialization.
691 * In this case, the user passes down the configurator object
692 * and performs all the initialization code on the object.
693 *
694 * \param timeoutSeconds Maximum time to wait up to in seconds.
695 * \returns StatusCode of the set command
696 */
697 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds);
698
699 /**
700 * \brief Clear sticky fault: Device boot while detecting the enable
701 * signal
702 *
703 * This will wait up to #DefaultTimeoutSeconds.
704 *
705 * This is available in the configurator in case the user wants
706 * to initialize their device entirely without passing a device
707 * reference down to the code that performs the initialization.
708 * In this case, the user passes down the configurator object
709 * and performs all the initialization code on the object.
710 *
711 * \returns StatusCode of the set command
712 */
714 {
715 return ClearStickyFault_BootDuringEnable(DefaultTimeoutSeconds);
716 }
717 /**
718 * \brief Clear sticky fault: Device boot while detecting the enable
719 * signal
720 *
721 * This is available in the configurator in case the user wants
722 * to initialize their device entirely without passing a device
723 * reference down to the code that performs the initialization.
724 * In this case, the user passes down the configurator object
725 * and performs all the initialization code on the object.
726 *
727 * \param timeoutSeconds Maximum time to wait up to in seconds.
728 * \returns StatusCode of the set command
729 */
731
732 /**
733 * \brief Clear sticky fault: An unlicensed feature is in use, device
734 * may not behave as expected.
735 *
736 * This will wait up to #DefaultTimeoutSeconds.
737 *
738 * This is available in the configurator in case the user wants
739 * to initialize their device entirely without passing a device
740 * reference down to the code that performs the initialization.
741 * In this case, the user passes down the configurator object
742 * and performs all the initialization code on the object.
743 *
744 * \returns StatusCode of the set command
745 */
747 {
748 return ClearStickyFault_UnlicensedFeatureInUse(DefaultTimeoutSeconds);
749 }
750 /**
751 * \brief Clear sticky fault: An unlicensed feature is in use, device
752 * may not behave as expected.
753 *
754 * This is available in the configurator in case the user wants
755 * to initialize their device entirely without passing a device
756 * reference down to the code that performs the initialization.
757 * In this case, the user passes down the configurator object
758 * and performs all the initialization code on the object.
759 *
760 * \param timeoutSeconds Maximum time to wait up to in seconds.
761 * \returns StatusCode of the set command
762 */
764
765 /**
766 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
767 *
768 * This will wait up to #DefaultTimeoutSeconds.
769 *
770 * This is available in the configurator in case the user wants
771 * to initialize their device entirely without passing a device
772 * reference down to the code that performs the initialization.
773 * In this case, the user passes down the configurator object
774 * and performs all the initialization code on the object.
775 *
776 * \returns StatusCode of the set command
777 */
779 {
780 return ClearStickyFault_BootupAccelerometer(DefaultTimeoutSeconds);
781 }
782 /**
783 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
784 *
785 * This is available in the configurator in case the user wants
786 * to initialize their device entirely without passing a device
787 * reference down to the code that performs the initialization.
788 * In this case, the user passes down the configurator object
789 * and performs all the initialization code on the object.
790 *
791 * \param timeoutSeconds Maximum time to wait up to in seconds.
792 * \returns StatusCode of the set command
793 */
795
796 /**
797 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
798 *
799 * This will wait up to #DefaultTimeoutSeconds.
800 *
801 * This is available in the configurator in case the user wants
802 * to initialize their device entirely without passing a device
803 * reference down to the code that performs the initialization.
804 * In this case, the user passes down the configurator object
805 * and performs all the initialization code on the object.
806 *
807 * \returns StatusCode of the set command
808 */
810 {
811 return ClearStickyFault_BootupGyroscope(DefaultTimeoutSeconds);
812 }
813 /**
814 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
815 *
816 * This is available in the configurator in case the user wants
817 * to initialize their device entirely without passing a device
818 * reference down to the code that performs the initialization.
819 * In this case, the user passes down the configurator object
820 * and performs all the initialization code on the object.
821 *
822 * \param timeoutSeconds Maximum time to wait up to in seconds.
823 * \returns StatusCode of the set command
824 */
825 ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds);
826
827 /**
828 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
829 *
830 * This will wait up to #DefaultTimeoutSeconds.
831 *
832 * This is available in the configurator in case the user wants
833 * to initialize their device entirely without passing a device
834 * reference down to the code that performs the initialization.
835 * In this case, the user passes down the configurator object
836 * and performs all the initialization code on the object.
837 *
838 * \returns StatusCode of the set command
839 */
841 {
842 return ClearStickyFault_BootupMagnetometer(DefaultTimeoutSeconds);
843 }
844 /**
845 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
846 *
847 * This is available in the configurator in case the user wants
848 * to initialize their device entirely without passing a device
849 * reference down to the code that performs the initialization.
850 * In this case, the user passes down the configurator object
851 * and performs all the initialization code on the object.
852 *
853 * \param timeoutSeconds Maximum time to wait up to in seconds.
854 * \returns StatusCode of the set command
855 */
857
858 /**
859 * \brief Clear sticky fault: Motion Detected during bootup.
860 *
861 * This will wait up to #DefaultTimeoutSeconds.
862 *
863 * This is available in the configurator in case the user wants
864 * to initialize their device entirely without passing a device
865 * reference down to the code that performs the initialization.
866 * In this case, the user passes down the configurator object
867 * and performs all the initialization code on the object.
868 *
869 * \returns StatusCode of the set command
870 */
872 {
873 return ClearStickyFault_BootIntoMotion(DefaultTimeoutSeconds);
874 }
875 /**
876 * \brief Clear sticky fault: Motion Detected during bootup.
877 *
878 * This is available in the configurator in case the user wants
879 * to initialize their device entirely without passing a device
880 * reference down to the code that performs the initialization.
881 * In this case, the user passes down the configurator object
882 * and performs all the initialization code on the object.
883 *
884 * \param timeoutSeconds Maximum time to wait up to in seconds.
885 * \returns StatusCode of the set command
886 */
887 ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds);
888
889 /**
890 * \brief Clear sticky fault: Motion stack data acquisition was slower
891 * than expected
892 *
893 * This will wait up to #DefaultTimeoutSeconds.
894 *
895 * This is available in the configurator in case the user wants
896 * to initialize their device entirely without passing a device
897 * reference down to the code that performs the initialization.
898 * In this case, the user passes down the configurator object
899 * and performs all the initialization code on the object.
900 *
901 * \returns StatusCode of the set command
902 */
904 {
905 return ClearStickyFault_DataAcquiredLate(DefaultTimeoutSeconds);
906 }
907 /**
908 * \brief Clear sticky fault: Motion stack data acquisition was slower
909 * than expected
910 *
911 * This is available in the configurator in case the user wants
912 * to initialize their device entirely without passing a device
913 * reference down to the code that performs the initialization.
914 * In this case, the user passes down the configurator object
915 * and performs all the initialization code on the object.
916 *
917 * \param timeoutSeconds Maximum time to wait up to in seconds.
918 * \returns StatusCode of the set command
919 */
921
922 /**
923 * \brief Clear sticky fault: Motion stack loop time was slower than
924 * expected.
925 *
926 * This will wait up to #DefaultTimeoutSeconds.
927 *
928 * This is available in the configurator in case the user wants
929 * to initialize their device entirely without passing a device
930 * reference down to the code that performs the initialization.
931 * In this case, the user passes down the configurator object
932 * and performs all the initialization code on the object.
933 *
934 * \returns StatusCode of the set command
935 */
937 {
938 return ClearStickyFault_LoopTimeSlow(DefaultTimeoutSeconds);
939 }
940 /**
941 * \brief Clear sticky fault: Motion stack loop time was slower than
942 * expected.
943 *
944 * This is available in the configurator in case the user wants
945 * to initialize their device entirely without passing a device
946 * reference down to the code that performs the initialization.
947 * In this case, the user passes down the configurator object
948 * and performs all the initialization code on the object.
949 *
950 * \param timeoutSeconds Maximum time to wait up to in seconds.
951 * \returns StatusCode of the set command
952 */
953 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds);
954
955 /**
956 * \brief Clear sticky fault: Magnetometer values are saturated
957 *
958 * This will wait up to #DefaultTimeoutSeconds.
959 *
960 * This is available in the configurator in case the user wants
961 * to initialize their device entirely without passing a device
962 * reference down to the code that performs the initialization.
963 * In this case, the user passes down the configurator object
964 * and performs all the initialization code on the object.
965 *
966 * \returns StatusCode of the set command
967 */
969 {
970 return ClearStickyFault_SaturatedMagnetometer(DefaultTimeoutSeconds);
971 }
972 /**
973 * \brief Clear sticky fault: Magnetometer values are saturated
974 *
975 * This is available in the configurator in case the user wants
976 * to initialize their device entirely without passing a device
977 * reference down to the code that performs the initialization.
978 * In this case, the user passes down the configurator object
979 * and performs all the initialization code on the object.
980 *
981 * \param timeoutSeconds Maximum time to wait up to in seconds.
982 * \returns StatusCode of the set command
983 */
985
986 /**
987 * \brief Clear sticky fault: Accelerometer values are saturated
988 *
989 * This will wait up to #DefaultTimeoutSeconds.
990 *
991 * This is available in the configurator in case the user wants
992 * to initialize their device entirely without passing a device
993 * reference down to the code that performs the initialization.
994 * In this case, the user passes down the configurator object
995 * and performs all the initialization code on the object.
996 *
997 * \returns StatusCode of the set command
998 */
1000 {
1001 return ClearStickyFault_SaturatedAccelerometer(DefaultTimeoutSeconds);
1002 }
1003 /**
1004 * \brief Clear sticky fault: Accelerometer values are saturated
1005 *
1006 * This is available in the configurator in case the user wants
1007 * to initialize their device entirely without passing a device
1008 * reference down to the code that performs the initialization.
1009 * In this case, the user passes down the configurator object
1010 * and performs all the initialization code on the object.
1011 *
1012 * \param timeoutSeconds Maximum time to wait up to in seconds.
1013 * \returns StatusCode of the set command
1014 */
1016
1017 /**
1018 * \brief Clear sticky fault: Gyroscope values are saturated
1019 *
1020 * This will wait up to #DefaultTimeoutSeconds.
1021 *
1022 * This is available in the configurator in case the user wants
1023 * to initialize their device entirely without passing a device
1024 * reference down to the code that performs the initialization.
1025 * In this case, the user passes down the configurator object
1026 * and performs all the initialization code on the object.
1027 *
1028 * \returns StatusCode of the set command
1029 */
1031 {
1032 return ClearStickyFault_SaturatedGyroscope(DefaultTimeoutSeconds);
1033 }
1034 /**
1035 * \brief Clear sticky fault: Gyroscope values are saturated
1036 *
1037 * This is available in the configurator in case the user wants
1038 * to initialize their device entirely without passing a device
1039 * reference down to the code that performs the initialization.
1040 * In this case, the user passes down the configurator object
1041 * and performs all the initialization code on the object.
1042 *
1043 * \param timeoutSeconds Maximum time to wait up to in seconds.
1044 * \returns StatusCode of the set command
1045 */
1047};
1048
1049}
1050
1051namespace hardware {
1052namespace core {
1053
1054#if defined(_WIN32) || defined(_WIN64)
1055#pragma warning(push)
1056#pragma warning(disable : 4250)
1057#endif
1058
1059/**
1060 * Class description for the Pigeon 2 IMU sensor that measures orientation.
1061 */
1063{
1064private:
1066
1067public:
1068 /**
1069 * \brief The configuration class for this device.
1070 */
1072
1073 /**
1074 * Constructs a new Pigeon 2 sensor object.
1075 *
1076 * \param deviceId ID of the device, as configured in Phoenix Tuner
1077 * \param canbus The CAN bus this device is on
1078 */
1079 CorePigeon2(int deviceId, CANBus canbus = {});
1080
1081 /**
1082 * Constructs a new Pigeon 2 sensor object.
1083 *
1084 * \param deviceId ID of the device, as configured in Phoenix Tuner
1085 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
1086 * - "rio" for the native roboRIO CAN bus
1087 * - CANivore name or serial number
1088 * - SocketCAN interface (non-FRC Linux only)
1089 * - "*" for any CANivore seen by the program
1090 * - empty string (default) to select the default for the system:
1091 * - "rio" on roboRIO
1092 * - "can0" on Linux
1093 * - "*" on Windows
1094 *
1095 * \deprecated Constructing devices with a CAN bus string is deprecated for removal
1096 * in the 2027 season. Construct devices using a CANBus instance instead.
1097 */
1098 CorePigeon2(int deviceId, std::string canbus);
1099
1100 /**
1101 * \brief Gets the configurator for this Pigeon2
1102 *
1103 * \details Gets the configurator for this Pigeon2
1104 *
1105 * \returns Configurator for this Pigeon2
1106 */
1108 {
1109 return _configs;
1110 }
1111
1112 /**
1113 * \brief Gets the configurator for this Pigeon2
1114 *
1115 * \details Gets the configurator for this Pigeon2
1116 *
1117 * \returns Configurator for this Pigeon2
1118 */
1120 {
1121 return _configs;
1122 }
1123
1124
1125private:
1126 std::unique_ptr<sim::Pigeon2SimState> _simState{};
1127public:
1128 /**
1129 * \brief Get the simulation state for this device.
1130 *
1131 * \details This function reuses an allocated simulation
1132 * state object, so it is safe to call this function multiple
1133 * times in a robot loop.
1134 *
1135 * \returns Simulation state
1136 */
1138 {
1139 if (_simState == nullptr)
1140 _simState = std::make_unique<sim::Pigeon2SimState>(*this);
1141 return *_simState;
1142 }
1143
1144
1145
1146 /**
1147 * \brief App Major Version number.
1148 *
1149 * - Minimum Value: 0
1150 * - Maximum Value: 255
1151 * - Default Value: 0
1152 * - Units:
1153 *
1154 * Default Rates:
1155 * - CAN: 4.0 Hz
1156 *
1157 * This refreshes and returns a cached StatusSignal object.
1158 *
1159 * \param refresh Whether to refresh the StatusSignal before returning it;
1160 * defaults to true
1161 * \returns VersionMajor Status Signal Object
1162 */
1163 StatusSignal<int> &GetVersionMajor(bool refresh = true);
1164
1165 /**
1166 * \brief App Minor Version number.
1167 *
1168 * - Minimum Value: 0
1169 * - Maximum Value: 255
1170 * - Default Value: 0
1171 * - Units:
1172 *
1173 * Default Rates:
1174 * - CAN: 4.0 Hz
1175 *
1176 * This refreshes and returns a cached StatusSignal object.
1177 *
1178 * \param refresh Whether to refresh the StatusSignal before returning it;
1179 * defaults to true
1180 * \returns VersionMinor Status Signal Object
1181 */
1182 StatusSignal<int> &GetVersionMinor(bool refresh = true);
1183
1184 /**
1185 * \brief App Bugfix Version number.
1186 *
1187 * - Minimum Value: 0
1188 * - Maximum Value: 255
1189 * - Default Value: 0
1190 * - Units:
1191 *
1192 * Default Rates:
1193 * - CAN: 4.0 Hz
1194 *
1195 * This refreshes and returns a cached StatusSignal object.
1196 *
1197 * \param refresh Whether to refresh the StatusSignal before returning it;
1198 * defaults to true
1199 * \returns VersionBugfix Status Signal Object
1200 */
1202
1203 /**
1204 * \brief App Build Version number.
1205 *
1206 * - Minimum Value: 0
1207 * - Maximum Value: 255
1208 * - Default Value: 0
1209 * - Units:
1210 *
1211 * Default Rates:
1212 * - CAN: 4.0 Hz
1213 *
1214 * This refreshes and returns a cached StatusSignal object.
1215 *
1216 * \param refresh Whether to refresh the StatusSignal before returning it;
1217 * defaults to true
1218 * \returns VersionBuild Status Signal Object
1219 */
1220 StatusSignal<int> &GetVersionBuild(bool refresh = true);
1221
1222 /**
1223 * \brief Full Version of firmware in device. The format is a four
1224 * byte value.
1225 *
1226 * - Minimum Value: 0
1227 * - Maximum Value: 4294967295
1228 * - Default Value: 0
1229 * - Units:
1230 *
1231 * Default Rates:
1232 * - CAN: 4.0 Hz
1233 *
1234 * This refreshes and returns a cached StatusSignal object.
1235 *
1236 * \param refresh Whether to refresh the StatusSignal before returning it;
1237 * defaults to true
1238 * \returns Version Status Signal Object
1239 */
1240 StatusSignal<int> &GetVersion(bool refresh = true);
1241
1242 /**
1243 * \brief Integer representing all fault flags reported by the device.
1244 *
1245 * \details These are device specific and are not used directly in
1246 * typical applications. Use the signal specific GetFault_*() methods
1247 * instead.
1248 *
1249 * - Minimum Value: 0
1250 * - Maximum Value: 4294967295
1251 * - Default Value: 0
1252 * - Units:
1253 *
1254 * Default Rates:
1255 * - CAN: 4.0 Hz
1256 *
1257 * This refreshes and returns a cached StatusSignal object.
1258 *
1259 * \param refresh Whether to refresh the StatusSignal before returning it;
1260 * defaults to true
1261 * \returns FaultField Status Signal Object
1262 */
1263 StatusSignal<int> &GetFaultField(bool refresh = true);
1264
1265 /**
1266 * \brief Integer representing all (persistent) sticky fault flags
1267 * reported by the device.
1268 *
1269 * \details These are device specific and are not used directly in
1270 * typical applications. Use the signal specific GetStickyFault_*()
1271 * methods instead.
1272 *
1273 * - Minimum Value: 0
1274 * - Maximum Value: 4294967295
1275 * - Default Value: 0
1276 * - Units:
1277 *
1278 * Default Rates:
1279 * - CAN: 4.0 Hz
1280 *
1281 * This refreshes and returns a cached StatusSignal object.
1282 *
1283 * \param refresh Whether to refresh the StatusSignal before returning it;
1284 * defaults to true
1285 * \returns StickyFaultField Status Signal Object
1286 */
1288
1289 /**
1290 * \brief Current reported yaw of the Pigeon2.
1291 *
1292 * - Minimum Value: -368640.0
1293 * - Maximum Value: 368639.99725341797
1294 * - Default Value: 0
1295 * - Units: deg
1296 *
1297 * Default Rates:
1298 * - CAN 2.0: 100.0 Hz
1299 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1300 *
1301 * This refreshes and returns a cached StatusSignal object.
1302 *
1303 * \param refresh Whether to refresh the StatusSignal before returning it;
1304 * defaults to true
1305 * \returns Yaw Status Signal Object
1306 */
1308
1309 /**
1310 * \brief Current reported pitch of the Pigeon2.
1311 *
1312 * - Minimum Value: -90.0
1313 * - Maximum Value: 89.9560546875
1314 * - Default Value: 0
1315 * - Units: deg
1316 *
1317 * Default Rates:
1318 * - CAN 2.0: 100.0 Hz
1319 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1320 *
1321 * This refreshes and returns a cached StatusSignal object.
1322 *
1323 * \param refresh Whether to refresh the StatusSignal before returning it;
1324 * defaults to true
1325 * \returns Pitch Status Signal Object
1326 */
1328
1329 /**
1330 * \brief Current reported roll of the Pigeon2.
1331 *
1332 * - Minimum Value: -180.0
1333 * - Maximum Value: 179.9560546875
1334 * - Default Value: 0
1335 * - Units: deg
1336 *
1337 * Default Rates:
1338 * - CAN 2.0: 100.0 Hz
1339 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1340 *
1341 * This refreshes and returns a cached StatusSignal object.
1342 *
1343 * \param refresh Whether to refresh the StatusSignal before returning it;
1344 * defaults to true
1345 * \returns Roll Status Signal Object
1346 */
1348
1349 /**
1350 * \brief The W component of the reported Quaternion.
1351 *
1352 * - Minimum Value: -1.0001220852154804
1353 * - Maximum Value: 1.0
1354 * - Default Value: 0
1355 * - Units:
1356 *
1357 * Default Rates:
1358 * - CAN 2.0: 50.0 Hz
1359 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1360 *
1361 * This refreshes and returns a cached StatusSignal object.
1362 *
1363 * \param refresh Whether to refresh the StatusSignal before returning it;
1364 * defaults to true
1365 * \returns QuatW Status Signal Object
1366 */
1368
1369 /**
1370 * \brief The X component of the reported Quaternion.
1371 *
1372 * - Minimum Value: -1.0001220852154804
1373 * - Maximum Value: 1.0
1374 * - Default Value: 0
1375 * - Units:
1376 *
1377 * Default Rates:
1378 * - CAN 2.0: 50.0 Hz
1379 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1380 *
1381 * This refreshes and returns a cached StatusSignal object.
1382 *
1383 * \param refresh Whether to refresh the StatusSignal before returning it;
1384 * defaults to true
1385 * \returns QuatX Status Signal Object
1386 */
1388
1389 /**
1390 * \brief The Y component of the reported Quaternion.
1391 *
1392 * - Minimum Value: -1.0001220852154804
1393 * - Maximum Value: 1.0
1394 * - Default Value: 0
1395 * - Units:
1396 *
1397 * Default Rates:
1398 * - CAN 2.0: 50.0 Hz
1399 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1400 *
1401 * This refreshes and returns a cached StatusSignal object.
1402 *
1403 * \param refresh Whether to refresh the StatusSignal before returning it;
1404 * defaults to true
1405 * \returns QuatY Status Signal Object
1406 */
1408
1409 /**
1410 * \brief The Z component of the reported Quaternion.
1411 *
1412 * - Minimum Value: -1.0001220852154804
1413 * - Maximum Value: 1.0
1414 * - Default Value: 0
1415 * - Units:
1416 *
1417 * Default Rates:
1418 * - CAN 2.0: 50.0 Hz
1419 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1420 *
1421 * This refreshes and returns a cached StatusSignal object.
1422 *
1423 * \param refresh Whether to refresh the StatusSignal before returning it;
1424 * defaults to true
1425 * \returns QuatZ Status Signal Object
1426 */
1428
1429 /**
1430 * \brief The X component of the gravity vector.
1431 *
1432 * \details This is the X component of the reported gravity-vector.
1433 * The gravity vector is not the acceleration experienced by the
1434 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1435 * can be used for mechanisms that are linearly related to gravity,
1436 * such as an arm pivoting about a point, as the contribution of
1437 * gravity to the arm is directly proportional to the contribution of
1438 * gravity about one of these primary axis.
1439 *
1440 * - Minimum Value: -1.000030518509476
1441 * - Maximum Value: 1.0
1442 * - Default Value: 0
1443 * - Units:
1444 *
1445 * Default Rates:
1446 * - CAN 2.0: 10.0 Hz
1447 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1448 *
1449 * This refreshes and returns a cached StatusSignal object.
1450 *
1451 * \param refresh Whether to refresh the StatusSignal before returning it;
1452 * defaults to true
1453 * \returns GravityVectorX Status Signal Object
1454 */
1456
1457 /**
1458 * \brief The Y component of the gravity vector.
1459 *
1460 * \details This is the X component of the reported gravity-vector.
1461 * The gravity vector is not the acceleration experienced by the
1462 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1463 * can be used for mechanisms that are linearly related to gravity,
1464 * such as an arm pivoting about a point, as the contribution of
1465 * gravity to the arm is directly proportional to the contribution of
1466 * gravity about one of these primary axis.
1467 *
1468 * - Minimum Value: -1.000030518509476
1469 * - Maximum Value: 1.0
1470 * - Default Value: 0
1471 * - Units:
1472 *
1473 * Default Rates:
1474 * - CAN 2.0: 10.0 Hz
1475 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1476 *
1477 * This refreshes and returns a cached StatusSignal object.
1478 *
1479 * \param refresh Whether to refresh the StatusSignal before returning it;
1480 * defaults to true
1481 * \returns GravityVectorY Status Signal Object
1482 */
1484
1485 /**
1486 * \brief The Z component of the gravity vector.
1487 *
1488 * \details This is the Z component of the reported gravity-vector.
1489 * The gravity vector is not the acceleration experienced by the
1490 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1491 * can be used for mechanisms that are linearly related to gravity,
1492 * such as an arm pivoting about a point, as the contribution of
1493 * gravity to the arm is directly proportional to the contribution of
1494 * gravity about one of these primary axis.
1495 *
1496 * - Minimum Value: -1.000030518509476
1497 * - Maximum Value: 1.0
1498 * - Default Value: 0
1499 * - Units:
1500 *
1501 * Default Rates:
1502 * - CAN 2.0: 10.0 Hz
1503 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1504 *
1505 * This refreshes and returns a cached StatusSignal object.
1506 *
1507 * \param refresh Whether to refresh the StatusSignal before returning it;
1508 * defaults to true
1509 * \returns GravityVectorZ Status Signal Object
1510 */
1512
1513 /**
1514 * \brief Temperature of the Pigeon 2.
1515 *
1516 * - Minimum Value: -128.0
1517 * - Maximum Value: 127.99609375
1518 * - Default Value: 0
1519 * - Units: ℃
1520 *
1521 * Default Rates:
1522 * - CAN 2.0: 4.0 Hz
1523 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1524 *
1525 * This refreshes and returns a cached StatusSignal object.
1526 *
1527 * \param refresh Whether to refresh the StatusSignal before returning it;
1528 * defaults to true
1529 * \returns Temperature Status Signal Object
1530 */
1532
1533 /**
1534 * \brief Whether the no-motion calibration feature is enabled.
1535 *
1536 * - Default Value: 0
1537 *
1538 * Default Rates:
1539 * - CAN 2.0: 4.0 Hz
1540 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1541 *
1542 * This refreshes and returns a cached StatusSignal object.
1543 *
1544 * \param refresh Whether to refresh the StatusSignal before returning it;
1545 * defaults to true
1546 * \returns NoMotionEnabled Status Signal Object
1547 */
1549
1550 /**
1551 * \brief The number of times a no-motion event occurred, wraps at 15.
1552 *
1553 * - Minimum Value: 0
1554 * - Maximum Value: 15
1555 * - Default Value: 0
1556 * - Units:
1557 *
1558 * Default Rates:
1559 * - CAN 2.0: 4.0 Hz
1560 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1561 *
1562 * This refreshes and returns a cached StatusSignal object.
1563 *
1564 * \param refresh Whether to refresh the StatusSignal before returning it;
1565 * defaults to true
1566 * \returns NoMotionCount Status Signal Object
1567 */
1569
1570 /**
1571 * \brief Whether the temperature-compensation feature is disabled.
1572 *
1573 * - Default Value: 0
1574 *
1575 * Default Rates:
1576 * - CAN 2.0: 4.0 Hz
1577 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1578 *
1579 * This refreshes and returns a cached StatusSignal object.
1580 *
1581 * \param refresh Whether to refresh the StatusSignal before returning it;
1582 * defaults to true
1583 * \returns TemperatureCompensationDisabled Status Signal Object
1584 */
1586
1587 /**
1588 * \brief How long the Pigeon 2's been up in seconds, caps at 255
1589 * seconds.
1590 *
1591 * - Minimum Value: 0
1592 * - Maximum Value: 255
1593 * - Default Value: 0
1594 * - Units: s
1595 *
1596 * Default Rates:
1597 * - CAN 2.0: 4.0 Hz
1598 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1599 *
1600 * This refreshes and returns a cached StatusSignal object.
1601 *
1602 * \param refresh Whether to refresh the StatusSignal before returning it;
1603 * defaults to true
1604 * \returns UpTime Status Signal Object
1605 */
1607
1608 /**
1609 * \brief The accumulated gyro about the X axis without any sensor
1610 * fusing.
1611 *
1612 * - Minimum Value: -23040.0
1613 * - Maximum Value: 23039.9560546875
1614 * - Default Value: 0
1615 * - Units: deg
1616 *
1617 * Default Rates:
1618 * - CAN 2.0: 4.0 Hz
1619 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1620 *
1621 * This refreshes and returns a cached StatusSignal object.
1622 *
1623 * \param refresh Whether to refresh the StatusSignal before returning it;
1624 * defaults to true
1625 * \returns AccumGyroX Status Signal Object
1626 */
1628
1629 /**
1630 * \brief The accumulated gyro about the Y axis without any sensor
1631 * fusing.
1632 *
1633 * - Minimum Value: -23040.0
1634 * - Maximum Value: 23039.9560546875
1635 * - Default Value: 0
1636 * - Units: deg
1637 *
1638 * Default Rates:
1639 * - CAN 2.0: 4.0 Hz
1640 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1641 *
1642 * This refreshes and returns a cached StatusSignal object.
1643 *
1644 * \param refresh Whether to refresh the StatusSignal before returning it;
1645 * defaults to true
1646 * \returns AccumGyroY Status Signal Object
1647 */
1649
1650 /**
1651 * \brief The accumulated gyro about the Z axis without any sensor
1652 * fusing.
1653 *
1654 * - Minimum Value: -23040.0
1655 * - Maximum Value: 23039.9560546875
1656 * - Default Value: 0
1657 * - Units: deg
1658 *
1659 * Default Rates:
1660 * - CAN 2.0: 4.0 Hz
1661 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1662 *
1663 * This refreshes and returns a cached StatusSignal object.
1664 *
1665 * \param refresh Whether to refresh the StatusSignal before returning it;
1666 * defaults to true
1667 * \returns AccumGyroZ Status Signal Object
1668 */
1670
1671 /**
1672 * \brief The angular velocity (ω) of the Pigeon 2 about the X axis
1673 * with respect to the world frame. This value is mount-calibrated.
1674 *
1675 * - Minimum Value: -2048.0
1676 * - Maximum Value: 2047.99609375
1677 * - Default Value: 0
1678 * - Units: dps
1679 *
1680 * Default Rates:
1681 * - CAN 2.0: 10.0 Hz
1682 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1683 *
1684 * This refreshes and returns a cached StatusSignal object.
1685 *
1686 * \param refresh Whether to refresh the StatusSignal before returning it;
1687 * defaults to true
1688 * \returns AngularVelocityXWorld Status Signal Object
1689 */
1691
1692 /**
1693 * \brief The angular velocity (ω) of the Pigeon 2 about the Y axis
1694 * with respect to the world frame. This value is mount-calibrated.
1695 *
1696 * - Minimum Value: -2048.0
1697 * - Maximum Value: 2047.99609375
1698 * - Default Value: 0
1699 * - Units: dps
1700 *
1701 * Default Rates:
1702 * - CAN 2.0: 10.0 Hz
1703 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1704 *
1705 * This refreshes and returns a cached StatusSignal object.
1706 *
1707 * \param refresh Whether to refresh the StatusSignal before returning it;
1708 * defaults to true
1709 * \returns AngularVelocityYWorld Status Signal Object
1710 */
1712
1713 /**
1714 * \brief The angular velocity (ω) of the Pigeon 2 about the Z axis
1715 * with respect to the world frame. This value is mount-calibrated.
1716 *
1717 * - Minimum Value: -2048.0
1718 * - Maximum Value: 2047.99609375
1719 * - Default Value: 0
1720 * - Units: dps
1721 *
1722 * Default Rates:
1723 * - CAN 2.0: 10.0 Hz
1724 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1725 *
1726 * This refreshes and returns a cached StatusSignal object.
1727 *
1728 * \param refresh Whether to refresh the StatusSignal before returning it;
1729 * defaults to true
1730 * \returns AngularVelocityZWorld Status Signal Object
1731 */
1733
1734 /**
1735 * \brief The acceleration measured by Pigeon2 in the X direction.
1736 *
1737 * \details This value includes the acceleration due to gravity. If
1738 * this is undesirable, get the gravity vector and subtract out the
1739 * contribution in this direction.
1740 *
1741 * - Minimum Value: -2.0
1742 * - Maximum Value: 1.99993896484375
1743 * - Default Value: 0
1744 * - Units: g
1745 *
1746 * Default Rates:
1747 * - CAN 2.0: 10.0 Hz
1748 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1749 *
1750 * This refreshes and returns a cached StatusSignal object.
1751 *
1752 * \param refresh Whether to refresh the StatusSignal before returning it;
1753 * defaults to true
1754 * \returns AccelerationX Status Signal Object
1755 */
1757
1758 /**
1759 * \brief The acceleration measured by Pigeon2 in the Y direction.
1760 *
1761 * \details This value includes the acceleration due to gravity. If
1762 * this is undesirable, get the gravity vector and subtract out the
1763 * contribution in this direction.
1764 *
1765 * - Minimum Value: -2.0
1766 * - Maximum Value: 1.99993896484375
1767 * - Default Value: 0
1768 * - Units: g
1769 *
1770 * Default Rates:
1771 * - CAN 2.0: 10.0 Hz
1772 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1773 *
1774 * This refreshes and returns a cached StatusSignal object.
1775 *
1776 * \param refresh Whether to refresh the StatusSignal before returning it;
1777 * defaults to true
1778 * \returns AccelerationY Status Signal Object
1779 */
1781
1782 /**
1783 * \brief The acceleration measured by Pigeon2 in the Z direction.
1784 *
1785 * \details This value includes the acceleration due to gravity. If
1786 * this is undesirable, get the gravity vector and subtract out the
1787 * contribution in this direction.
1788 *
1789 * - Minimum Value: -2.0
1790 * - Maximum Value: 1.99993896484375
1791 * - Default Value: 0
1792 * - Units: g
1793 *
1794 * Default Rates:
1795 * - CAN 2.0: 10.0 Hz
1796 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1797 *
1798 * This refreshes and returns a cached StatusSignal object.
1799 *
1800 * \param refresh Whether to refresh the StatusSignal before returning it;
1801 * defaults to true
1802 * \returns AccelerationZ Status Signal Object
1803 */
1805
1806 /**
1807 * \brief Measured supply voltage to the Pigeon2.
1808 *
1809 * - Minimum Value: 0.0
1810 * - Maximum Value: 31.99951171875
1811 * - Default Value: 0
1812 * - Units: V
1813 *
1814 * Default Rates:
1815 * - CAN 2.0: 4.0 Hz
1816 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1817 *
1818 * This refreshes and returns a cached StatusSignal object.
1819 *
1820 * \param refresh Whether to refresh the StatusSignal before returning it;
1821 * defaults to true
1822 * \returns SupplyVoltage Status Signal Object
1823 */
1825
1826 /**
1827 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1828 * X axis.
1829 *
1830 * \details This value is not mount-calibrated.
1831 *
1832 * - Minimum Value: -1998.048780487805
1833 * - Maximum Value: 1997.987804878049
1834 * - Default Value: 0
1835 * - Units: dps
1836 *
1837 * Default Rates:
1838 * - CAN: 4.0 Hz
1839 *
1840 * This refreshes and returns a cached StatusSignal object.
1841 *
1842 * \param refresh Whether to refresh the StatusSignal before returning it;
1843 * defaults to true
1844 * \returns AngularVelocityXDevice Status Signal Object
1845 */
1847
1848 /**
1849 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1850 * Y axis.
1851 *
1852 * \details This value is not mount-calibrated.
1853 *
1854 * - Minimum Value: -1998.048780487805
1855 * - Maximum Value: 1997.987804878049
1856 * - Default Value: 0
1857 * - Units: dps
1858 *
1859 * Default Rates:
1860 * - CAN: 4.0 Hz
1861 *
1862 * This refreshes and returns a cached StatusSignal object.
1863 *
1864 * \param refresh Whether to refresh the StatusSignal before returning it;
1865 * defaults to true
1866 * \returns AngularVelocityYDevice Status Signal Object
1867 */
1869
1870 /**
1871 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1872 * Z axis.
1873 *
1874 * \details This value is not mount-calibrated.
1875 *
1876 * - Minimum Value: -1998.048780487805
1877 * - Maximum Value: 1997.987804878049
1878 * - Default Value: 0
1879 * - Units: dps
1880 *
1881 * Default Rates:
1882 * - CAN: 4.0 Hz
1883 *
1884 * This refreshes and returns a cached StatusSignal object.
1885 *
1886 * \param refresh Whether to refresh the StatusSignal before returning it;
1887 * defaults to true
1888 * \returns AngularVelocityZDevice Status Signal Object
1889 */
1891
1892 /**
1893 * \brief The biased magnitude of the magnetic field measured by the
1894 * Pigeon 2 in the X direction. This is only valid after performing a
1895 * magnetometer calibration.
1896 *
1897 * - Minimum Value: -19660.8
1898 * - Maximum Value: 19660.2
1899 * - Default Value: 0
1900 * - Units: uT
1901 *
1902 * Default Rates:
1903 * - CAN: 4.0 Hz
1904 *
1905 * This refreshes and returns a cached StatusSignal object.
1906 *
1907 * \param refresh Whether to refresh the StatusSignal before returning it;
1908 * defaults to true
1909 * \returns MagneticFieldX Status Signal Object
1910 */
1912
1913 /**
1914 * \brief The biased magnitude of the magnetic field measured by the
1915 * Pigeon 2 in the Y direction. This is only valid after performing a
1916 * magnetometer calibration.
1917 *
1918 * - Minimum Value: -19660.8
1919 * - Maximum Value: 19660.2
1920 * - Default Value: 0
1921 * - Units: uT
1922 *
1923 * Default Rates:
1924 * - CAN: 4.0 Hz
1925 *
1926 * This refreshes and returns a cached StatusSignal object.
1927 *
1928 * \param refresh Whether to refresh the StatusSignal before returning it;
1929 * defaults to true
1930 * \returns MagneticFieldY Status Signal Object
1931 */
1933
1934 /**
1935 * \brief The biased magnitude of the magnetic field measured by the
1936 * Pigeon 2 in the Z direction. This is only valid after performing a
1937 * magnetometer calibration.
1938 *
1939 * - Minimum Value: -19660.8
1940 * - Maximum Value: 19660.2
1941 * - Default Value: 0
1942 * - Units: uT
1943 *
1944 * Default Rates:
1945 * - CAN: 4.0 Hz
1946 *
1947 * This refreshes and returns a cached StatusSignal object.
1948 *
1949 * \param refresh Whether to refresh the StatusSignal before returning it;
1950 * defaults to true
1951 * \returns MagneticFieldZ Status Signal Object
1952 */
1954
1955 /**
1956 * \brief The raw magnitude of the magnetic field measured by the
1957 * Pigeon 2 in the X direction. This is only valid after performing a
1958 * magnetometer calibration.
1959 *
1960 * - Minimum Value: -19660.8
1961 * - Maximum Value: 19660.2
1962 * - Default Value: 0
1963 * - Units: uT
1964 *
1965 * Default Rates:
1966 * - CAN: 4.0 Hz
1967 *
1968 * This refreshes and returns a cached StatusSignal object.
1969 *
1970 * \param refresh Whether to refresh the StatusSignal before returning it;
1971 * defaults to true
1972 * \returns RawMagneticFieldX Status Signal Object
1973 */
1975
1976 /**
1977 * \brief The raw magnitude of the magnetic field measured by the
1978 * Pigeon 2 in the Y direction. This is only valid after performing a
1979 * magnetometer calibration.
1980 *
1981 * - Minimum Value: -19660.8
1982 * - Maximum Value: 19660.2
1983 * - Default Value: 0
1984 * - Units: uT
1985 *
1986 * Default Rates:
1987 * - CAN: 4.0 Hz
1988 *
1989 * This refreshes and returns a cached StatusSignal object.
1990 *
1991 * \param refresh Whether to refresh the StatusSignal before returning it;
1992 * defaults to true
1993 * \returns RawMagneticFieldY Status Signal Object
1994 */
1996
1997 /**
1998 * \brief The raw magnitude of the magnetic field measured by the
1999 * Pigeon 2 in the Z direction. This is only valid after performing a
2000 * magnetometer calibration.
2001 *
2002 * - Minimum Value: -19660.8
2003 * - Maximum Value: 19660.2
2004 * - Default Value: 0
2005 * - Units: uT
2006 *
2007 * Default Rates:
2008 * - CAN: 4.0 Hz
2009 *
2010 * This refreshes and returns a cached StatusSignal object.
2011 *
2012 * \param refresh Whether to refresh the StatusSignal before returning it;
2013 * defaults to true
2014 * \returns RawMagneticFieldZ Status Signal Object
2015 */
2017
2018 /**
2019 * \brief Whether the device is Phoenix Pro licensed.
2020 *
2021 * - Default Value: False
2022 *
2023 * Default Rates:
2024 * - CAN: 4.0 Hz
2025 *
2026 * This refreshes and returns a cached StatusSignal object.
2027 *
2028 * \param refresh Whether to refresh the StatusSignal before returning it;
2029 * defaults to true
2030 * \returns IsProLicensed Status Signal Object
2031 */
2033
2034 /**
2035 * \brief Hardware fault occurred
2036 *
2037 * - Default Value: False
2038 *
2039 * Default Rates:
2040 * - CAN: 4.0 Hz
2041 *
2042 * This refreshes and returns a cached StatusSignal object.
2043 *
2044 * \param refresh Whether to refresh the StatusSignal before returning it;
2045 * defaults to true
2046 * \returns Fault_Hardware Status Signal Object
2047 */
2049
2050 /**
2051 * \brief Hardware fault occurred
2052 *
2053 * - Default Value: False
2054 *
2055 * Default Rates:
2056 * - CAN: 4.0 Hz
2057 *
2058 * This refreshes and returns a cached StatusSignal object.
2059 *
2060 * \param refresh Whether to refresh the StatusSignal before returning it;
2061 * defaults to true
2062 * \returns StickyFault_Hardware Status Signal Object
2063 */
2065
2066 /**
2067 * \brief Device supply voltage dropped to near brownout levels
2068 *
2069 * - Default Value: False
2070 *
2071 * Default Rates:
2072 * - CAN: 4.0 Hz
2073 *
2074 * This refreshes and returns a cached StatusSignal object.
2075 *
2076 * \param refresh Whether to refresh the StatusSignal before returning it;
2077 * defaults to true
2078 * \returns Fault_Undervoltage Status Signal Object
2079 */
2081
2082 /**
2083 * \brief Device supply voltage dropped to near brownout levels
2084 *
2085 * - Default Value: False
2086 *
2087 * Default Rates:
2088 * - CAN: 4.0 Hz
2089 *
2090 * This refreshes and returns a cached StatusSignal object.
2091 *
2092 * \param refresh Whether to refresh the StatusSignal before returning it;
2093 * defaults to true
2094 * \returns StickyFault_Undervoltage Status Signal Object
2095 */
2097
2098 /**
2099 * \brief Device boot while detecting the enable signal
2100 *
2101 * - Default Value: False
2102 *
2103 * Default Rates:
2104 * - CAN: 4.0 Hz
2105 *
2106 * This refreshes and returns a cached StatusSignal object.
2107 *
2108 * \param refresh Whether to refresh the StatusSignal before returning it;
2109 * defaults to true
2110 * \returns Fault_BootDuringEnable Status Signal Object
2111 */
2113
2114 /**
2115 * \brief Device boot while detecting the enable signal
2116 *
2117 * - Default Value: False
2118 *
2119 * Default Rates:
2120 * - CAN: 4.0 Hz
2121 *
2122 * This refreshes and returns a cached StatusSignal object.
2123 *
2124 * \param refresh Whether to refresh the StatusSignal before returning it;
2125 * defaults to true
2126 * \returns StickyFault_BootDuringEnable Status Signal Object
2127 */
2129
2130 /**
2131 * \brief An unlicensed feature is in use, device may not behave as
2132 * expected.
2133 *
2134 * - Default Value: False
2135 *
2136 * Default Rates:
2137 * - CAN: 4.0 Hz
2138 *
2139 * This refreshes and returns a cached StatusSignal object.
2140 *
2141 * \param refresh Whether to refresh the StatusSignal before returning it;
2142 * defaults to true
2143 * \returns Fault_UnlicensedFeatureInUse Status Signal Object
2144 */
2146
2147 /**
2148 * \brief An unlicensed feature is in use, device may not behave as
2149 * expected.
2150 *
2151 * - Default Value: False
2152 *
2153 * Default Rates:
2154 * - CAN: 4.0 Hz
2155 *
2156 * This refreshes and returns a cached StatusSignal object.
2157 *
2158 * \param refresh Whether to refresh the StatusSignal before returning it;
2159 * defaults to true
2160 * \returns StickyFault_UnlicensedFeatureInUse Status Signal Object
2161 */
2163
2164 /**
2165 * \brief Bootup checks failed: Accelerometer
2166 *
2167 * - Default Value: False
2168 *
2169 * Default Rates:
2170 * - CAN: 4.0 Hz
2171 *
2172 * This refreshes and returns a cached StatusSignal object.
2173 *
2174 * \param refresh Whether to refresh the StatusSignal before returning it;
2175 * defaults to true
2176 * \returns Fault_BootupAccelerometer Status Signal Object
2177 */
2179
2180 /**
2181 * \brief Bootup checks failed: Accelerometer
2182 *
2183 * - Default Value: False
2184 *
2185 * Default Rates:
2186 * - CAN: 4.0 Hz
2187 *
2188 * This refreshes and returns a cached StatusSignal object.
2189 *
2190 * \param refresh Whether to refresh the StatusSignal before returning it;
2191 * defaults to true
2192 * \returns StickyFault_BootupAccelerometer Status Signal Object
2193 */
2195
2196 /**
2197 * \brief Bootup checks failed: Gyroscope
2198 *
2199 * - Default Value: False
2200 *
2201 * Default Rates:
2202 * - CAN: 4.0 Hz
2203 *
2204 * This refreshes and returns a cached StatusSignal object.
2205 *
2206 * \param refresh Whether to refresh the StatusSignal before returning it;
2207 * defaults to true
2208 * \returns Fault_BootupGyroscope Status Signal Object
2209 */
2211
2212 /**
2213 * \brief Bootup checks failed: Gyroscope
2214 *
2215 * - Default Value: False
2216 *
2217 * Default Rates:
2218 * - CAN: 4.0 Hz
2219 *
2220 * This refreshes and returns a cached StatusSignal object.
2221 *
2222 * \param refresh Whether to refresh the StatusSignal before returning it;
2223 * defaults to true
2224 * \returns StickyFault_BootupGyroscope Status Signal Object
2225 */
2227
2228 /**
2229 * \brief Bootup checks failed: Magnetometer
2230 *
2231 * - Default Value: False
2232 *
2233 * Default Rates:
2234 * - CAN: 4.0 Hz
2235 *
2236 * This refreshes and returns a cached StatusSignal object.
2237 *
2238 * \param refresh Whether to refresh the StatusSignal before returning it;
2239 * defaults to true
2240 * \returns Fault_BootupMagnetometer Status Signal Object
2241 */
2243
2244 /**
2245 * \brief Bootup checks failed: Magnetometer
2246 *
2247 * - Default Value: False
2248 *
2249 * Default Rates:
2250 * - CAN: 4.0 Hz
2251 *
2252 * This refreshes and returns a cached StatusSignal object.
2253 *
2254 * \param refresh Whether to refresh the StatusSignal before returning it;
2255 * defaults to true
2256 * \returns StickyFault_BootupMagnetometer Status Signal Object
2257 */
2259
2260 /**
2261 * \brief Motion Detected during bootup.
2262 *
2263 * - Default Value: False
2264 *
2265 * Default Rates:
2266 * - CAN: 4.0 Hz
2267 *
2268 * This refreshes and returns a cached StatusSignal object.
2269 *
2270 * \param refresh Whether to refresh the StatusSignal before returning it;
2271 * defaults to true
2272 * \returns Fault_BootIntoMotion Status Signal Object
2273 */
2275
2276 /**
2277 * \brief Motion Detected during bootup.
2278 *
2279 * - Default Value: False
2280 *
2281 * Default Rates:
2282 * - CAN: 4.0 Hz
2283 *
2284 * This refreshes and returns a cached StatusSignal object.
2285 *
2286 * \param refresh Whether to refresh the StatusSignal before returning it;
2287 * defaults to true
2288 * \returns StickyFault_BootIntoMotion Status Signal Object
2289 */
2291
2292 /**
2293 * \brief Motion stack data acquisition was slower than expected
2294 *
2295 * - Default Value: False
2296 *
2297 * Default Rates:
2298 * - CAN: 4.0 Hz
2299 *
2300 * This refreshes and returns a cached StatusSignal object.
2301 *
2302 * \param refresh Whether to refresh the StatusSignal before returning it;
2303 * defaults to true
2304 * \returns Fault_DataAcquiredLate Status Signal Object
2305 */
2307
2308 /**
2309 * \brief Motion stack data acquisition was slower than expected
2310 *
2311 * - Default Value: False
2312 *
2313 * Default Rates:
2314 * - CAN: 4.0 Hz
2315 *
2316 * This refreshes and returns a cached StatusSignal object.
2317 *
2318 * \param refresh Whether to refresh the StatusSignal before returning it;
2319 * defaults to true
2320 * \returns StickyFault_DataAcquiredLate Status Signal Object
2321 */
2323
2324 /**
2325 * \brief Motion stack loop time was slower than expected.
2326 *
2327 * - Default Value: False
2328 *
2329 * Default Rates:
2330 * - CAN: 4.0 Hz
2331 *
2332 * This refreshes and returns a cached StatusSignal object.
2333 *
2334 * \param refresh Whether to refresh the StatusSignal before returning it;
2335 * defaults to true
2336 * \returns Fault_LoopTimeSlow Status Signal Object
2337 */
2339
2340 /**
2341 * \brief Motion stack loop time was slower than expected.
2342 *
2343 * - Default Value: False
2344 *
2345 * Default Rates:
2346 * - CAN: 4.0 Hz
2347 *
2348 * This refreshes and returns a cached StatusSignal object.
2349 *
2350 * \param refresh Whether to refresh the StatusSignal before returning it;
2351 * defaults to true
2352 * \returns StickyFault_LoopTimeSlow Status Signal Object
2353 */
2355
2356 /**
2357 * \brief Magnetometer values are saturated
2358 *
2359 * - Default Value: False
2360 *
2361 * Default Rates:
2362 * - CAN: 4.0 Hz
2363 *
2364 * This refreshes and returns a cached StatusSignal object.
2365 *
2366 * \param refresh Whether to refresh the StatusSignal before returning it;
2367 * defaults to true
2368 * \returns Fault_SaturatedMagnetometer Status Signal Object
2369 */
2371
2372 /**
2373 * \brief Magnetometer values are saturated
2374 *
2375 * - Default Value: False
2376 *
2377 * Default Rates:
2378 * - CAN: 4.0 Hz
2379 *
2380 * This refreshes and returns a cached StatusSignal object.
2381 *
2382 * \param refresh Whether to refresh the StatusSignal before returning it;
2383 * defaults to true
2384 * \returns StickyFault_SaturatedMagnetometer Status Signal Object
2385 */
2387
2388 /**
2389 * \brief Accelerometer values are saturated
2390 *
2391 * - Default Value: False
2392 *
2393 * Default Rates:
2394 * - CAN: 4.0 Hz
2395 *
2396 * This refreshes and returns a cached StatusSignal object.
2397 *
2398 * \param refresh Whether to refresh the StatusSignal before returning it;
2399 * defaults to true
2400 * \returns Fault_SaturatedAccelerometer Status Signal Object
2401 */
2403
2404 /**
2405 * \brief Accelerometer values are saturated
2406 *
2407 * - Default Value: False
2408 *
2409 * Default Rates:
2410 * - CAN: 4.0 Hz
2411 *
2412 * This refreshes and returns a cached StatusSignal object.
2413 *
2414 * \param refresh Whether to refresh the StatusSignal before returning it;
2415 * defaults to true
2416 * \returns StickyFault_SaturatedAccelerometer Status Signal Object
2417 */
2419
2420 /**
2421 * \brief Gyroscope values are saturated
2422 *
2423 * - Default Value: False
2424 *
2425 * Default Rates:
2426 * - CAN: 4.0 Hz
2427 *
2428 * This refreshes and returns a cached StatusSignal object.
2429 *
2430 * \param refresh Whether to refresh the StatusSignal before returning it;
2431 * defaults to true
2432 * \returns Fault_SaturatedGyroscope Status Signal Object
2433 */
2435
2436 /**
2437 * \brief Gyroscope values are saturated
2438 *
2439 * - Default Value: False
2440 *
2441 * Default Rates:
2442 * - CAN: 4.0 Hz
2443 *
2444 * This refreshes and returns a cached StatusSignal object.
2445 *
2446 * \param refresh Whether to refresh the StatusSignal before returning it;
2447 * defaults to true
2448 * \returns StickyFault_SaturatedGyroscope Status Signal Object
2449 */
2451
2452
2453
2454 /**
2455 * \brief Control device with generic control request object. User must make
2456 * sure the specified object is castable to a valid control request,
2457 * otherwise this function will fail at run-time and return the NotSupported
2458 * StatusCode
2459 *
2460 * \param request Control object to request of the device
2461 * \returns Status Code of the request, 0 is OK
2462 */
2464
2465
2466 /**
2467 * \brief The yaw to set the Pigeon2 to right now.
2468 *
2469 * \param newValue Value to set to. Units are in deg.
2470 * \param timeoutSeconds Maximum time to wait up to in seconds.
2471 * \returns StatusCode of the set command
2472 */
2473 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
2474 {
2475 return GetConfigurator().SetYaw(newValue, timeoutSeconds);
2476 }
2477 /**
2478 * \brief The yaw to set the Pigeon2 to right now.
2479 *
2480 * This will wait up to 0.100 seconds (100ms) by default.
2481 *
2482 * \param newValue Value to set to. Units are in deg.
2483 * \returns StatusCode of the set command
2484 */
2485 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
2486 {
2487 return SetYaw(newValue, 0.100_s);
2488 }
2489
2490 /**
2491 * \brief Clear the sticky faults in the device.
2492 *
2493 * \details This typically has no impact on the device functionality.
2494 * Instead, it just clears telemetry faults that are accessible via
2495 * API and Tuner Self-Test.
2496 *
2497 * \param timeoutSeconds Maximum time to wait up to in seconds.
2498 * \returns StatusCode of the set command
2499 */
2500 ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
2501 {
2502 return GetConfigurator().ClearStickyFaults(timeoutSeconds);
2503 }
2504 /**
2505 * \brief Clear the sticky faults in the device.
2506 *
2507 * \details This typically has no impact on the device functionality.
2508 * Instead, it just clears telemetry faults that are accessible via
2509 * API and Tuner Self-Test.
2510 *
2511 * This will wait up to 0.100 seconds (100ms) by default.
2512 *
2513 * \returns StatusCode of the set command
2514 */
2516 {
2517 return ClearStickyFaults(0.100_s);
2518 }
2519
2520 /**
2521 * \brief Clear sticky fault: Hardware fault occurred
2522 *
2523 * \param timeoutSeconds Maximum time to wait up to in seconds.
2524 * \returns StatusCode of the set command
2525 */
2526 ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
2527 {
2528 return GetConfigurator().ClearStickyFault_Hardware(timeoutSeconds);
2529 }
2530 /**
2531 * \brief Clear sticky fault: Hardware fault occurred
2532 *
2533 * This will wait up to 0.100 seconds (100ms) by default.
2534 *
2535 * \returns StatusCode of the set command
2536 */
2538 {
2539 return ClearStickyFault_Hardware(0.100_s);
2540 }
2541
2542 /**
2543 * \brief Clear sticky fault: Device supply voltage dropped to near
2544 * brownout levels
2545 *
2546 * \param timeoutSeconds Maximum time to wait up to in seconds.
2547 * \returns StatusCode of the set command
2548 */
2549 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
2550 {
2551 return GetConfigurator().ClearStickyFault_Undervoltage(timeoutSeconds);
2552 }
2553 /**
2554 * \brief Clear sticky fault: Device supply voltage dropped to near
2555 * brownout levels
2556 *
2557 * This will wait up to 0.100 seconds (100ms) by default.
2558 *
2559 * \returns StatusCode of the set command
2560 */
2562 {
2563 return ClearStickyFault_Undervoltage(0.100_s);
2564 }
2565
2566 /**
2567 * \brief Clear sticky fault: Device boot while detecting the enable
2568 * signal
2569 *
2570 * \param timeoutSeconds Maximum time to wait up to in seconds.
2571 * \returns StatusCode of the set command
2572 */
2574 {
2575 return GetConfigurator().ClearStickyFault_BootDuringEnable(timeoutSeconds);
2576 }
2577 /**
2578 * \brief Clear sticky fault: Device boot while detecting the enable
2579 * signal
2580 *
2581 * This will wait up to 0.100 seconds (100ms) by default.
2582 *
2583 * \returns StatusCode of the set command
2584 */
2586 {
2587 return ClearStickyFault_BootDuringEnable(0.100_s);
2588 }
2589
2590 /**
2591 * \brief Clear sticky fault: An unlicensed feature is in use, device
2592 * may not behave as expected.
2593 *
2594 * \param timeoutSeconds Maximum time to wait up to in seconds.
2595 * \returns StatusCode of the set command
2596 */
2598 {
2599 return GetConfigurator().ClearStickyFault_UnlicensedFeatureInUse(timeoutSeconds);
2600 }
2601 /**
2602 * \brief Clear sticky fault: An unlicensed feature is in use, device
2603 * may not behave as expected.
2604 *
2605 * This will wait up to 0.100 seconds (100ms) by default.
2606 *
2607 * \returns StatusCode of the set command
2608 */
2610 {
2611 return ClearStickyFault_UnlicensedFeatureInUse(0.100_s);
2612 }
2613
2614 /**
2615 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2616 *
2617 * \param timeoutSeconds Maximum time to wait up to in seconds.
2618 * \returns StatusCode of the set command
2619 */
2621 {
2622 return GetConfigurator().ClearStickyFault_BootupAccelerometer(timeoutSeconds);
2623 }
2624 /**
2625 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2626 *
2627 * This will wait up to 0.100 seconds (100ms) by default.
2628 *
2629 * \returns StatusCode of the set command
2630 */
2632 {
2633 return ClearStickyFault_BootupAccelerometer(0.100_s);
2634 }
2635
2636 /**
2637 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2638 *
2639 * \param timeoutSeconds Maximum time to wait up to in seconds.
2640 * \returns StatusCode of the set command
2641 */
2643 {
2644 return GetConfigurator().ClearStickyFault_BootupGyroscope(timeoutSeconds);
2645 }
2646 /**
2647 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2648 *
2649 * This will wait up to 0.100 seconds (100ms) by default.
2650 *
2651 * \returns StatusCode of the set command
2652 */
2654 {
2655 return ClearStickyFault_BootupGyroscope(0.100_s);
2656 }
2657
2658 /**
2659 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2660 *
2661 * \param timeoutSeconds Maximum time to wait up to in seconds.
2662 * \returns StatusCode of the set command
2663 */
2665 {
2666 return GetConfigurator().ClearStickyFault_BootupMagnetometer(timeoutSeconds);
2667 }
2668 /**
2669 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2670 *
2671 * This will wait up to 0.100 seconds (100ms) by default.
2672 *
2673 * \returns StatusCode of the set command
2674 */
2676 {
2677 return ClearStickyFault_BootupMagnetometer(0.100_s);
2678 }
2679
2680 /**
2681 * \brief Clear sticky fault: Motion Detected during bootup.
2682 *
2683 * \param timeoutSeconds Maximum time to wait up to in seconds.
2684 * \returns StatusCode of the set command
2685 */
2687 {
2688 return GetConfigurator().ClearStickyFault_BootIntoMotion(timeoutSeconds);
2689 }
2690 /**
2691 * \brief Clear sticky fault: Motion Detected during bootup.
2692 *
2693 * This will wait up to 0.100 seconds (100ms) by default.
2694 *
2695 * \returns StatusCode of the set command
2696 */
2698 {
2699 return ClearStickyFault_BootIntoMotion(0.100_s);
2700 }
2701
2702 /**
2703 * \brief Clear sticky fault: Motion stack data acquisition was slower
2704 * than expected
2705 *
2706 * \param timeoutSeconds Maximum time to wait up to in seconds.
2707 * \returns StatusCode of the set command
2708 */
2710 {
2711 return GetConfigurator().ClearStickyFault_DataAcquiredLate(timeoutSeconds);
2712 }
2713 /**
2714 * \brief Clear sticky fault: Motion stack data acquisition was slower
2715 * than expected
2716 *
2717 * This will wait up to 0.100 seconds (100ms) by default.
2718 *
2719 * \returns StatusCode of the set command
2720 */
2722 {
2723 return ClearStickyFault_DataAcquiredLate(0.100_s);
2724 }
2725
2726 /**
2727 * \brief Clear sticky fault: Motion stack loop time was slower than
2728 * expected.
2729 *
2730 * \param timeoutSeconds Maximum time to wait up to in seconds.
2731 * \returns StatusCode of the set command
2732 */
2733 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
2734 {
2735 return GetConfigurator().ClearStickyFault_LoopTimeSlow(timeoutSeconds);
2736 }
2737 /**
2738 * \brief Clear sticky fault: Motion stack loop time was slower than
2739 * expected.
2740 *
2741 * This will wait up to 0.100 seconds (100ms) by default.
2742 *
2743 * \returns StatusCode of the set command
2744 */
2746 {
2747 return ClearStickyFault_LoopTimeSlow(0.100_s);
2748 }
2749
2750 /**
2751 * \brief Clear sticky fault: Magnetometer values are saturated
2752 *
2753 * \param timeoutSeconds Maximum time to wait up to in seconds.
2754 * \returns StatusCode of the set command
2755 */
2757 {
2758 return GetConfigurator().ClearStickyFault_SaturatedMagnetometer(timeoutSeconds);
2759 }
2760 /**
2761 * \brief Clear sticky fault: Magnetometer values are saturated
2762 *
2763 * This will wait up to 0.100 seconds (100ms) by default.
2764 *
2765 * \returns StatusCode of the set command
2766 */
2768 {
2769 return ClearStickyFault_SaturatedMagnetometer(0.100_s);
2770 }
2771
2772 /**
2773 * \brief Clear sticky fault: Accelerometer values are saturated
2774 *
2775 * \param timeoutSeconds Maximum time to wait up to in seconds.
2776 * \returns StatusCode of the set command
2777 */
2779 {
2780 return GetConfigurator().ClearStickyFault_SaturatedAccelerometer(timeoutSeconds);
2781 }
2782 /**
2783 * \brief Clear sticky fault: Accelerometer values are saturated
2784 *
2785 * This will wait up to 0.100 seconds (100ms) by default.
2786 *
2787 * \returns StatusCode of the set command
2788 */
2790 {
2791 return ClearStickyFault_SaturatedAccelerometer(0.100_s);
2792 }
2793
2794 /**
2795 * \brief Clear sticky fault: Gyroscope values are saturated
2796 *
2797 * \param timeoutSeconds Maximum time to wait up to in seconds.
2798 * \returns StatusCode of the set command
2799 */
2801 {
2802 return GetConfigurator().ClearStickyFault_SaturatedGyroscope(timeoutSeconds);
2803 }
2804 /**
2805 * \brief Clear sticky fault: Gyroscope values are saturated
2806 *
2807 * This will wait up to 0.100 seconds (100ms) by default.
2808 *
2809 * \returns StatusCode of the set command
2810 */
2812 {
2813 return ClearStickyFault_SaturatedGyroscope(0.100_s);
2814 }
2815};
2816
2817#if defined(_WIN32) || defined(_WIN64)
2818#pragma warning(pop)
2819#endif
2820
2821}
2822}
2823
2824}
2825}
2826
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Represents a status signal with data of type T, and operations available to retrieve information abou...
Definition StatusSignal.hpp:474
Custom Params.
Definition CustomParamsConfigs.hpp:23
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Configs to trim the Pigeon2's gyroscope.
Definition GyroTrimConfigs.hpp:27
std::string Serialize() const final
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Configs for Pigeon 2's Mount Pose configuration.
Definition MountPoseConfigs.hpp:25
std::string Serialize() const final
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Definition Configuration.hpp:17
Definition Configurator.hpp:18
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:46
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Take a string and deserialize it to this configuration.
Pigeon2FeaturesConfigs Pigeon2Features
Configs to enable/disable various features of the Pigeon2.
Definition CorePigeon2.hpp:113
constexpr Pigeon2Configuration & WithGyroTrim(GyroTrimConfigs newGyroTrim)
Modifies this configuration's GyroTrim parameter and returns itself for method-chaining and easier to...
Definition CorePigeon2.hpp:176
CustomParamsConfigs CustomParams
Custom Params.
Definition CorePigeon2.hpp:126
GyroTrimConfigs GyroTrim
Configs to trim the Pigeon2's gyroscope.
Definition CorePigeon2.hpp:98
std::string ToString() const override
Get the string representation of this configuration.
bool FutureProofConfigs
True if we should factory default newer unsupported configs, false to leave newer unsupported configs...
Definition CorePigeon2.hpp:63
constexpr Pigeon2Configuration & WithMountPose(MountPoseConfigs newMountPose)
Modifies this configuration's MountPose parameter and returns itself for method-chaining and easier t...
Definition CorePigeon2.hpp:148
std::string Serialize() const final
Get the serialized form of this configuration.
MountPoseConfigs MountPose
Configs for Pigeon 2's Mount Pose configuration.
Definition CorePigeon2.hpp:80
constexpr Pigeon2Configuration & WithPigeon2Features(Pigeon2FeaturesConfigs newPigeon2Features)
Modifies this configuration's Pigeon2Features parameter and returns itself for method-chaining and ea...
Definition CorePigeon2.hpp:201
constexpr Pigeon2Configuration & WithCustomParams(CustomParamsConfigs newCustomParams)
Modifies this configuration's CustomParams parameter and returns itself for method-chaining and easie...
Definition CorePigeon2.hpp:224
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:251
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:713
ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:557
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:465
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:363
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:999
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:936
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:840
ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:543
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
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:316
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse()
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:746
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:452
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:577
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
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:497
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:680
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:871
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:302
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse(units::time::second_t timeoutSeconds)
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:332
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:483
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:437
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:968
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:778
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:405
ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:512
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:345
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:392
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:1030
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:809
ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:525
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:284
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:613
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:377
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:270
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:903
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:423
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:648
Configs to enable/disable various features of the Pigeon2.
Definition Pigeon2FeaturesConfigs.hpp:24
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Common interface implemented by all control requests.
Definition ControlRequest.hpp:27
Definition DeviceIdentifier.hpp:16
Parent class for all devices.
Definition ParentDevice.hpp:23
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1063
StatusSignal< bool > & GetTemperatureCompensationDisabled(bool refresh=true)
Whether the temperature-compensation feature is disabled.
StatusSignal< units::dimensionless::scalar_t > & GetQuatX(bool refresh=true)
The X component of the reported Quaternion.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityXWorld(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the X axis with respect to the world frame.
StatusSignal< units::angle::degree_t > & GetRoll(bool refresh=true)
Current reported roll of the Pigeon2.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationZ(bool refresh=true)
The acceleration measured by Pigeon2 in the Z direction.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityXDevice(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the device's X axis.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:2561
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2664
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:2631
ctre::phoenix::StatusCode SetControl(controls::ControlRequest const &request)
Control device with generic control request object.
StatusSignal< units::angle::degree_t > & GetYaw(bool refresh=true)
Current reported yaw of the Pigeon2.
StatusSignal< bool > & GetFault_SaturatedMagnetometer(bool refresh=true)
Magnetometer values are saturated.
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:2709
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse()
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:2609
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldX(bool refresh=true)
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignal< bool > & GetStickyFault_BootupGyroscope(bool refresh=true)
Bootup checks failed: Gyroscope.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY(bool refresh=true)
The Y component of the reported Quaternion.
StatusSignal< bool > & GetFault_LoopTimeSlow(bool refresh=true)
Motion stack loop time was slower than expected.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorY(bool refresh=true)
The Y component of the gravity vector.
StatusSignal< bool > & GetFault_SaturatedAccelerometer(bool refresh=true)
Accelerometer values are saturated.
StatusSignal< bool > & GetStickyFault_UnlicensedFeatureInUse(bool refresh=true)
An unlicensed feature is in use, device may not behave as expected.
StatusSignal< units::angle::degree_t > & GetAccumGyroX(bool refresh=true)
The accumulated gyro about the X axis without any sensor fusing.
StatusSignal< int > & GetVersion(bool refresh=true)
Full Version of firmware in device.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:2515
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2733
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZWorld(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the Z axis with respect to the world frame.
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:2721
StatusSignal< bool > & GetStickyFault_SaturatedMagnetometer(bool refresh=true)
Magnetometer values are saturated.
StatusSignal< bool > & GetStickyFault_BootIntoMotion(bool refresh=true)
Motion Detected during bootup.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZDevice(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
CorePigeon2(int deviceId, CANBus canbus={})
Constructs a new Pigeon 2 sensor object.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:2789
StatusSignal< int > & GetStickyFaultField(bool refresh=true)
Integer representing all (persistent) sticky fault flags reported by the device.
StatusSignal< bool > & GetNoMotionEnabled(bool refresh=true)
Whether the no-motion calibration feature is enabled.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:2811
StatusSignal< units::angle::degree_t > & GetPitch(bool refresh=true)
Current reported pitch of the Pigeon2.
configs::Pigeon2Configurator & GetConfigurator()
Gets the configurator for this Pigeon2.
Definition CorePigeon2.hpp:1107
StatusSignal< bool > & GetFault_SaturatedGyroscope(bool refresh=true)
Gyroscope values are saturated.
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:2537
StatusSignal< units::angle::degree_t > & GetAccumGyroY(bool refresh=true)
The accumulated gyro about the Y axis without any sensor fusing.
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:2473
StatusSignal< bool > & GetStickyFault_Undervoltage(bool refresh=true)
Device supply voltage dropped to near brownout levels.
StatusSignal< units::voltage::volt_t > & GetSupplyVoltage(bool refresh=true)
Measured supply voltage to the Pigeon2.
configs::Pigeon2Configurator const & GetConfigurator() const
Gets the configurator for this Pigeon2.
Definition CorePigeon2.hpp:1119
StatusSignal< bool > & GetFault_BootupGyroscope(bool refresh=true)
Bootup checks failed: Gyroscope.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationX(bool refresh=true)
The acceleration measured by Pigeon2 in the X direction.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:2800
StatusSignal< units::dimensionless::scalar_t > & GetQuatW(bool refresh=true)
The W component of the reported Quaternion.
StatusSignal< bool > & GetStickyFault_Hardware(bool refresh=true)
Hardware fault occurred.
StatusSignal< bool > & GetStickyFault_SaturatedAccelerometer(bool refresh=true)
Accelerometer values are saturated.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityYDevice(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:2500
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2756
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2653
StatusSignal< bool > & GetFault_Undervoltage(bool refresh=true)
Device supply voltage dropped to near brownout levels.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:2697
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2767
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldX(bool refresh=true)
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignal< units::dimensionless::scalar_t > & GetNoMotionCount(bool refresh=true)
The number of times a no-motion event occurred, wraps at 15.
StatusSignal< units::time::second_t > & GetUpTime(bool refresh=true)
How long the Pigeon 2's been up in seconds, caps at 255 seconds.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:2573
StatusSignal< int > & GetVersionMajor(bool refresh=true)
App Major Version number.
StatusSignal< bool > & GetFault_BootIntoMotion(bool refresh=true)
Motion Detected during bootup.
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2745
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldZ(bool refresh=true)
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorX(bool refresh=true)
The X component of the gravity vector.
StatusSignal< bool > & GetStickyFault_SaturatedGyroscope(bool refresh=true)
Gyroscope values are saturated.
StatusSignal< bool > & GetFault_BootupAccelerometer(bool refresh=true)
Bootup checks failed: Accelerometer.
StatusSignal< bool > & GetStickyFault_BootDuringEnable(bool refresh=true)
Device boot while detecting the enable signal.
StatusSignal< int > & GetFaultField(bool refresh=true)
Integer representing all fault flags reported by the device.
StatusSignal< bool > & GetFault_BootupMagnetometer(bool refresh=true)
Bootup checks failed: Magnetometer.
StatusSignal< units::temperature::celsius_t > & GetTemperature(bool refresh=true)
Temperature of the Pigeon 2.
CorePigeon2(int deviceId, std::string canbus)
Constructs a new Pigeon 2 sensor object.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:2549
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2642
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:2686
StatusSignal< bool > & GetFault_UnlicensedFeatureInUse(bool refresh=true)
An unlicensed feature is in use, device may not behave as expected.
StatusSignal< int > & GetVersionBugfix(bool refresh=true)
App Bugfix Version number.
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse(units::time::second_t timeoutSeconds)
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:2597
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:2526
StatusSignal< bool > & GetFault_BootDuringEnable(bool refresh=true)
Device boot while detecting the enable signal.
StatusSignal< bool > & GetStickyFault_LoopTimeSlow(bool refresh=true)
Motion stack loop time was slower than expected.
StatusSignal< bool > & GetFault_DataAcquiredLate(bool refresh=true)
Motion stack data acquisition was slower than expected.
StatusSignal< bool > & GetIsProLicensed(bool refresh=true)
Whether the device is Phoenix Pro licensed.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:2485
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationY(bool refresh=true)
The acceleration measured by Pigeon2 in the Y direction.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:2585
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ(bool refresh=true)
The Z component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorZ(bool refresh=true)
The Z component of the gravity vector.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldZ(bool refresh=true)
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
StatusSignal< int > & GetVersionBuild(bool refresh=true)
App Build Version number.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:2620
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldY(bool refresh=true)
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
StatusSignal< bool > & GetStickyFault_BootupAccelerometer(bool refresh=true)
Bootup checks failed: Accelerometer.
StatusSignal< units::angle::degree_t > & GetAccumGyroZ(bool refresh=true)
The accumulated gyro about the Z axis without any sensor fusing.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldY(bool refresh=true)
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
StatusSignal< bool > & GetStickyFault_BootupMagnetometer(bool refresh=true)
Bootup checks failed: Magnetometer.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:2778
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2675
StatusSignal< bool > & GetStickyFault_DataAcquiredLate(bool refresh=true)
Motion stack data acquisition was slower than expected.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityYWorld(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the Y axis with respect to the world frame.
StatusSignal< int > & GetVersionMinor(bool refresh=true)
App Minor Version number.
StatusSignal< bool > & GetFault_Hardware(bool refresh=true)
Hardware fault occurred.
sim::Pigeon2SimState & GetSimState()
Get the simulation state for this device.
Definition CorePigeon2.hpp:1137
Class to control the state of a simulated hardware::Pigeon2.
Definition Pigeon2SimState.hpp:31
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
Definition motor_constants.h:14