CTRE Phoenix 6 C++ 26.50.0-alpha-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 <wpi/units/acceleration.hpp>
21#include <wpi/units/angle.hpp>
22#include <wpi/units/angular_velocity.hpp>
23#include <wpi/units/dimensionless.hpp>
24#include <wpi/units/magnetic_field_strength.hpp>
25#include <wpi/units/temperature.hpp>
26#include <wpi/units/time.hpp>
27#include <wpi/units/voltage.hpp>
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 */
250class Pigeon2Configurator : public ParentConfigurator
251{
252private:
253 Pigeon2Configurator(hardware::DeviceIdentifier id) :
254 ParentConfigurator{std::move(id)}
255 {}
256
258
259public:
260 /**
261 * \brief Applies the contents of the specified config to the device.
262 *
263 * This will wait up to #DefaultTimeoutSeconds.
264 *
265 * \details Call to apply the selected configs.
266 *
267 * \param configs Configs to apply against.
268 * \returns Status code of applying the configs
269 */
274
275 /**
276 * \brief Applies the contents of the specified config to the device.
277 *
278 * \details Call to apply the selected configs.
279 *
280 * \param configs Configs to apply against.
281 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
282 * \returns Status code of applying the configs
283 */
284 ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs, wpi::units::second_t timeoutSeconds)
285 {
286 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, configs.FutureProofConfigs, false);
287 }
288
289 /**
290 * \brief Applies the contents of the specified config to the device.
291 *
292 * This will wait up to #DefaultTimeoutSeconds.
293 *
294 * \details Call to apply the selected configs.
295 *
296 * \param configs Configs to apply against.
297 * \returns Status code of applying the configs
298 */
303
304 /**
305 * \brief Applies the contents of the specified config to the device.
306 *
307 * \details Call to apply the selected configs.
308 *
309 * \param configs Configs to apply against.
310 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
311 * \returns Status code of applying the configs
312 */
313 ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs, wpi::units::second_t timeoutSeconds)
314 {
315 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
316 }
317
318 /**
319 * \brief Applies the contents of the specified config to the device.
320 *
321 * This will wait up to #DefaultTimeoutSeconds.
322 *
323 * \details Call to apply the selected configs.
324 *
325 * \param configs Configs to apply against.
326 * \returns Status code of applying the configs
327 */
332
333 /**
334 * \brief Applies the contents of the specified config to the device.
335 *
336 * \details Call to apply the selected configs.
337 *
338 * \param configs Configs to apply against.
339 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
340 * \returns Status code of applying the configs
341 */
342 ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs, wpi::units::second_t timeoutSeconds)
343 {
344 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
345 }
346
347 /**
348 * \brief Applies the contents of the specified config to the device.
349 *
350 * This will wait up to #DefaultTimeoutSeconds.
351 *
352 * \details Call to apply the selected configs.
353 *
354 * \param configs Configs to apply against.
355 * \returns Status code of applying the configs
356 */
361
362 /**
363 * \brief Applies the contents of the specified config to the device.
364 *
365 * \details Call to apply the selected configs.
366 *
367 * \param configs Configs to apply against.
368 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
369 * \returns Status code of applying the configs
370 */
371 ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs, wpi::units::second_t timeoutSeconds)
372 {
373 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
374 }
375
376 /**
377 * \brief Applies the contents of the specified config to the device.
378 *
379 * This will wait up to #DefaultTimeoutSeconds.
380 *
381 * \details Call to apply the selected configs.
382 *
383 * \param configs Configs to apply against.
384 * \returns Status code of applying the configs
385 */
390
391 /**
392 * \brief Applies the contents of the specified config to the device.
393 *
394 * \details Call to apply the selected configs.
395 *
396 * \param configs Configs to apply against.
397 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
398 * \returns Status code of applying the configs
399 */
400 ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs, wpi::units::second_t timeoutSeconds)
401 {
402 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
403 }
404
405 /**
406 * \brief Refreshes the values of the specified config group.
407 *
408 * This will wait up to #DefaultTimeoutSeconds.
409 *
410 * \details Call to refresh the selected configs from the device.
411 *
412 * \param configs The configs to refresh
413 * \returns Status code of refreshing the configs
414 */
419
420 /**
421 * \brief Refreshes the values of the specified config group.
422 *
423 * \details Call to refresh the selected configs from the device.
424 *
425 * \param configs The configs to refresh
426 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
427 * \returns Status code of refreshing the configs
428 */
429 ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, wpi::units::second_t timeoutSeconds) const
430 {
431 std::string ref;
432 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
433 configs.Deserialize(ref);
434 return ret;
435 }
436
437 /**
438 * \brief Refreshes the values of the specified config group.
439 *
440 * This will wait up to #DefaultTimeoutSeconds.
441 *
442 * \details Call to refresh the selected configs from the device.
443 *
444 * \param configs The configs to refresh
445 * \returns Status code of refreshing the configs
446 */
451 /**
452 * \brief Refreshes the values of the specified config group.
453 *
454 * \details Call to refresh the selected configs from the device.
455 *
456 * \param configs The configs to refresh
457 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
458 * \returns Status code of refreshing the configs
459 */
460 ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, wpi::units::second_t timeoutSeconds) const
461 {
462 std::string ref;
463 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
464 configs.Deserialize(ref);
465 return ret;
466 }
467
468 /**
469 * \brief Refreshes the values of the specified config group.
470 *
471 * This will wait up to #DefaultTimeoutSeconds.
472 *
473 * \details Call to refresh the selected configs from the device.
474 *
475 * \param configs The configs to refresh
476 * \returns Status code of refreshing the configs
477 */
482 /**
483 * \brief Refreshes the values of the specified config group.
484 *
485 * \details Call to refresh the selected configs from the device.
486 *
487 * \param configs The configs to refresh
488 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
489 * \returns Status code of refreshing the configs
490 */
491 ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, wpi::units::second_t timeoutSeconds) const
492 {
493 std::string ref;
494 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
495 configs.Deserialize(ref);
496 return ret;
497 }
498
499 /**
500 * \brief Refreshes the values of the specified config group.
501 *
502 * This will wait up to #DefaultTimeoutSeconds.
503 *
504 * \details Call to refresh the selected configs from the device.
505 *
506 * \param configs The configs to refresh
507 * \returns Status code of refreshing the configs
508 */
513 /**
514 * \brief Refreshes the values of the specified config group.
515 *
516 * \details Call to refresh the selected configs from the device.
517 *
518 * \param configs The configs to refresh
519 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
520 * \returns Status code of refreshing the configs
521 */
522 ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, wpi::units::second_t timeoutSeconds) const
523 {
524 std::string ref;
525 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
526 configs.Deserialize(ref);
527 return ret;
528 }
529
530 /**
531 * \brief Refreshes the values of the specified config group.
532 *
533 * This will wait up to #DefaultTimeoutSeconds.
534 *
535 * \details Call to refresh the selected configs from the device.
536 *
537 * \param configs The configs to refresh
538 * \returns Status code of refreshing the configs
539 */
544 /**
545 * \brief Refreshes the values of the specified config group.
546 *
547 * \details Call to refresh the selected configs from the device.
548 *
549 * \param configs The configs to refresh
550 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
551 * \returns Status code of refreshing the configs
552 */
553 ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs, wpi::units::second_t timeoutSeconds) const
554 {
555 std::string ref;
556 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
557 configs.Deserialize(ref);
558 return ret;
559 }
560
561
562 /**
563 * \brief The yaw to set the Pigeon2 to right now.
564 *
565 * This will wait up to #DefaultTimeoutSeconds.
566 *
567 * This is available in the configurator in case the user wants
568 * to initialize their device entirely without passing a device
569 * reference down to the code that performs the initialization.
570 * In this case, the user passes down the configurator object
571 * and performs all the initialization code on the object.
572 *
573 * \param newValue Value to set to. Units are in deg.
574 * \returns StatusCode of the set command
575 */
576 ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue)
577 {
578 return SetYaw(newValue, DefaultTimeoutSeconds);
579 }
580 /**
581 * \brief The yaw to set the Pigeon2 to right now.
582 *
583 * This is available in the configurator in case the user wants
584 * to initialize their device entirely without passing a device
585 * reference down to the code that performs the initialization.
586 * In this case, the user passes down the configurator object
587 * and performs all the initialization code on the object.
588 *
589 * \param newValue Value to set to. Units are in deg.
590 * \param timeoutSeconds Maximum time to wait up to in seconds.
591 * \returns StatusCode of the set command
592 */
593 ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue, wpi::units::second_t timeoutSeconds);
594
595 /**
596 * \brief Clear the sticky faults in the device.
597 *
598 * \details This typically has no impact on the device functionality.
599 * Instead, it just clears telemetry faults that are accessible via
600 * API and Tuner Self-Test.
601 *
602 * This will wait up to #DefaultTimeoutSeconds.
603 *
604 * This is available in the configurator in case the user wants
605 * to initialize their device entirely without passing a device
606 * reference down to the code that performs the initialization.
607 * In this case, the user passes down the configurator object
608 * and performs all the initialization code on the object.
609 *
610 * \returns StatusCode of the set command
611 */
616 /**
617 * \brief Clear the sticky faults in the device.
618 *
619 * \details This typically has no impact on the device functionality.
620 * Instead, it just clears telemetry faults that are accessible via
621 * API and Tuner Self-Test.
622 *
623 * This is available in the configurator in case the user wants
624 * to initialize their device entirely without passing a device
625 * reference down to the code that performs the initialization.
626 * In this case, the user passes down the configurator object
627 * and performs all the initialization code on the object.
628 *
629 * \param timeoutSeconds Maximum time to wait up to in seconds.
630 * \returns StatusCode of the set command
631 */
632 ctre::phoenix::StatusCode ClearStickyFaults(wpi::units::second_t timeoutSeconds);
633
634 /**
635 * \brief Clear sticky fault: Hardware fault occurred
636 *
637 * This will wait up to #DefaultTimeoutSeconds.
638 *
639 * This is available in the configurator in case the user wants
640 * to initialize their device entirely without passing a device
641 * reference down to the code that performs the initialization.
642 * In this case, the user passes down the configurator object
643 * and performs all the initialization code on the object.
644 *
645 * \returns StatusCode of the set command
646 */
651 /**
652 * \brief Clear sticky fault: Hardware fault occurred
653 *
654 * This is available in the configurator in case the user wants
655 * to initialize their device entirely without passing a device
656 * reference down to the code that performs the initialization.
657 * In this case, the user passes down the configurator object
658 * and performs all the initialization code on the object.
659 *
660 * \param timeoutSeconds Maximum time to wait up to in seconds.
661 * \returns StatusCode of the set command
662 */
663 ctre::phoenix::StatusCode ClearStickyFault_Hardware(wpi::units::second_t timeoutSeconds);
664
665 /**
666 * \brief Clear sticky fault: Device supply voltage dropped to near
667 * brownout levels
668 *
669 * This will wait up to #DefaultTimeoutSeconds.
670 *
671 * This is available in the configurator in case the user wants
672 * to initialize their device entirely without passing a device
673 * reference down to the code that performs the initialization.
674 * In this case, the user passes down the configurator object
675 * and performs all the initialization code on the object.
676 *
677 * \returns StatusCode of the set command
678 */
683 /**
684 * \brief Clear sticky fault: Device supply voltage dropped to near
685 * brownout levels
686 *
687 * This is available in the configurator in case the user wants
688 * to initialize their device entirely without passing a device
689 * reference down to the code that performs the initialization.
690 * In this case, the user passes down the configurator object
691 * and performs all the initialization code on the object.
692 *
693 * \param timeoutSeconds Maximum time to wait up to in seconds.
694 * \returns StatusCode of the set command
695 */
696 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(wpi::units::second_t timeoutSeconds);
697
698 /**
699 * \brief Clear sticky fault: Device boot while detecting the enable
700 * signal
701 *
702 * This will wait up to #DefaultTimeoutSeconds.
703 *
704 * This is available in the configurator in case the user wants
705 * to initialize their device entirely without passing a device
706 * reference down to the code that performs the initialization.
707 * In this case, the user passes down the configurator object
708 * and performs all the initialization code on the object.
709 *
710 * \returns StatusCode of the set command
711 */
716 /**
717 * \brief Clear sticky fault: Device boot while detecting the enable
718 * signal
719 *
720 * This is available in the configurator in case the user wants
721 * to initialize their device entirely without passing a device
722 * reference down to the code that performs the initialization.
723 * In this case, the user passes down the configurator object
724 * and performs all the initialization code on the object.
725 *
726 * \param timeoutSeconds Maximum time to wait up to in seconds.
727 * \returns StatusCode of the set command
728 */
730
731 /**
732 * \brief Clear sticky fault: An unlicensed feature is in use, device
733 * may not behave as expected.
734 *
735 * This will wait up to #DefaultTimeoutSeconds.
736 *
737 * This is available in the configurator in case the user wants
738 * to initialize their device entirely without passing a device
739 * reference down to the code that performs the initialization.
740 * In this case, the user passes down the configurator object
741 * and performs all the initialization code on the object.
742 *
743 * \returns StatusCode of the set command
744 */
749 /**
750 * \brief Clear sticky fault: An unlicensed feature is in use, device
751 * may not behave as expected.
752 *
753 * This is available in the configurator in case the user wants
754 * to initialize their device entirely without passing a device
755 * reference down to the code that performs the initialization.
756 * In this case, the user passes down the configurator object
757 * and performs all the initialization code on the object.
758 *
759 * \param timeoutSeconds Maximum time to wait up to in seconds.
760 * \returns StatusCode of the set command
761 */
763
764 /**
765 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
766 *
767 * This will wait up to #DefaultTimeoutSeconds.
768 *
769 * This is available in the configurator in case the user wants
770 * to initialize their device entirely without passing a device
771 * reference down to the code that performs the initialization.
772 * In this case, the user passes down the configurator object
773 * and performs all the initialization code on the object.
774 *
775 * \returns StatusCode of the set command
776 */
781 /**
782 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
783 *
784 * This is available in the configurator in case the user wants
785 * to initialize their device entirely without passing a device
786 * reference down to the code that performs the initialization.
787 * In this case, the user passes down the configurator object
788 * and performs all the initialization code on the object.
789 *
790 * \param timeoutSeconds Maximum time to wait up to in seconds.
791 * \returns StatusCode of the set command
792 */
794
795 /**
796 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
797 *
798 * This will wait up to #DefaultTimeoutSeconds.
799 *
800 * This is available in the configurator in case the user wants
801 * to initialize their device entirely without passing a device
802 * reference down to the code that performs the initialization.
803 * In this case, the user passes down the configurator object
804 * and performs all the initialization code on the object.
805 *
806 * \returns StatusCode of the set command
807 */
812 /**
813 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
814 *
815 * This is available in the configurator in case the user wants
816 * to initialize their device entirely without passing a device
817 * reference down to the code that performs the initialization.
818 * In this case, the user passes down the configurator object
819 * and performs all the initialization code on the object.
820 *
821 * \param timeoutSeconds Maximum time to wait up to in seconds.
822 * \returns StatusCode of the set command
823 */
825
826 /**
827 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
828 *
829 * This will wait up to #DefaultTimeoutSeconds.
830 *
831 * This is available in the configurator in case the user wants
832 * to initialize their device entirely without passing a device
833 * reference down to the code that performs the initialization.
834 * In this case, the user passes down the configurator object
835 * and performs all the initialization code on the object.
836 *
837 * \returns StatusCode of the set command
838 */
843 /**
844 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
845 *
846 * This is available in the configurator in case the user wants
847 * to initialize their device entirely without passing a device
848 * reference down to the code that performs the initialization.
849 * In this case, the user passes down the configurator object
850 * and performs all the initialization code on the object.
851 *
852 * \param timeoutSeconds Maximum time to wait up to in seconds.
853 * \returns StatusCode of the set command
854 */
856
857 /**
858 * \brief Clear sticky fault: Motion Detected during bootup.
859 *
860 * This will wait up to #DefaultTimeoutSeconds.
861 *
862 * This is available in the configurator in case the user wants
863 * to initialize their device entirely without passing a device
864 * reference down to the code that performs the initialization.
865 * In this case, the user passes down the configurator object
866 * and performs all the initialization code on the object.
867 *
868 * \returns StatusCode of the set command
869 */
874 /**
875 * \brief Clear sticky fault: Motion Detected during bootup.
876 *
877 * This is available in the configurator in case the user wants
878 * to initialize their device entirely without passing a device
879 * reference down to the code that performs the initialization.
880 * In this case, the user passes down the configurator object
881 * and performs all the initialization code on the object.
882 *
883 * \param timeoutSeconds Maximum time to wait up to in seconds.
884 * \returns StatusCode of the set command
885 */
886 ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(wpi::units::second_t timeoutSeconds);
887
888 /**
889 * \brief Clear sticky fault: Motion stack data acquisition was slower
890 * than expected
891 *
892 * This will wait up to #DefaultTimeoutSeconds.
893 *
894 * This is available in the configurator in case the user wants
895 * to initialize their device entirely without passing a device
896 * reference down to the code that performs the initialization.
897 * In this case, the user passes down the configurator object
898 * and performs all the initialization code on the object.
899 *
900 * \returns StatusCode of the set command
901 */
906 /**
907 * \brief Clear sticky fault: Motion stack data acquisition was slower
908 * than expected
909 *
910 * This is available in the configurator in case the user wants
911 * to initialize their device entirely without passing a device
912 * reference down to the code that performs the initialization.
913 * In this case, the user passes down the configurator object
914 * and performs all the initialization code on the object.
915 *
916 * \param timeoutSeconds Maximum time to wait up to in seconds.
917 * \returns StatusCode of the set command
918 */
920
921 /**
922 * \brief Clear sticky fault: Motion stack loop time was slower than
923 * expected.
924 *
925 * This will wait up to #DefaultTimeoutSeconds.
926 *
927 * This is available in the configurator in case the user wants
928 * to initialize their device entirely without passing a device
929 * reference down to the code that performs the initialization.
930 * In this case, the user passes down the configurator object
931 * and performs all the initialization code on the object.
932 *
933 * \returns StatusCode of the set command
934 */
939 /**
940 * \brief Clear sticky fault: Motion stack loop time was slower than
941 * expected.
942 *
943 * This is available in the configurator in case the user wants
944 * to initialize their device entirely without passing a device
945 * reference down to the code that performs the initialization.
946 * In this case, the user passes down the configurator object
947 * and performs all the initialization code on the object.
948 *
949 * \param timeoutSeconds Maximum time to wait up to in seconds.
950 * \returns StatusCode of the set command
951 */
952 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(wpi::units::second_t timeoutSeconds);
953
954 /**
955 * \brief Clear sticky fault: Magnetometer values are saturated
956 *
957 * This will wait up to #DefaultTimeoutSeconds.
958 *
959 * This is available in the configurator in case the user wants
960 * to initialize their device entirely without passing a device
961 * reference down to the code that performs the initialization.
962 * In this case, the user passes down the configurator object
963 * and performs all the initialization code on the object.
964 *
965 * \returns StatusCode of the set command
966 */
971 /**
972 * \brief Clear sticky fault: Magnetometer values are saturated
973 *
974 * This is available in the configurator in case the user wants
975 * to initialize their device entirely without passing a device
976 * reference down to the code that performs the initialization.
977 * In this case, the user passes down the configurator object
978 * and performs all the initialization code on the object.
979 *
980 * \param timeoutSeconds Maximum time to wait up to in seconds.
981 * \returns StatusCode of the set command
982 */
984
985 /**
986 * \brief Clear sticky fault: Accelerometer values are saturated
987 *
988 * This will wait up to #DefaultTimeoutSeconds.
989 *
990 * This is available in the configurator in case the user wants
991 * to initialize their device entirely without passing a device
992 * reference down to the code that performs the initialization.
993 * In this case, the user passes down the configurator object
994 * and performs all the initialization code on the object.
995 *
996 * \returns StatusCode of the set command
997 */
1002 /**
1003 * \brief Clear sticky fault: Accelerometer values are saturated
1004 *
1005 * This is available in the configurator in case the user wants
1006 * to initialize their device entirely without passing a device
1007 * reference down to the code that performs the initialization.
1008 * In this case, the user passes down the configurator object
1009 * and performs all the initialization code on the object.
1010 *
1011 * \param timeoutSeconds Maximum time to wait up to in seconds.
1012 * \returns StatusCode of the set command
1013 */
1015
1016 /**
1017 * \brief Clear sticky fault: Gyroscope values are saturated
1018 *
1019 * This will wait up to #DefaultTimeoutSeconds.
1020 *
1021 * This is available in the configurator in case the user wants
1022 * to initialize their device entirely without passing a device
1023 * reference down to the code that performs the initialization.
1024 * In this case, the user passes down the configurator object
1025 * and performs all the initialization code on the object.
1026 *
1027 * \returns StatusCode of the set command
1028 */
1033 /**
1034 * \brief Clear sticky fault: Gyroscope values are saturated
1035 *
1036 * This is available in the configurator in case the user wants
1037 * to initialize their device entirely without passing a device
1038 * reference down to the code that performs the initialization.
1039 * In this case, the user passes down the configurator object
1040 * and performs all the initialization code on the object.
1041 *
1042 * \param timeoutSeconds Maximum time to wait up to in seconds.
1043 * \returns StatusCode of the set command
1044 */
1046};
1047
1048}
1049
1050namespace hardware {
1051namespace core {
1052
1053#if defined(_WIN32) || defined(_WIN64)
1054#pragma warning(push)
1055#pragma warning(disable : 4250)
1056#endif
1057
1058/**
1059 * Class description for the Pigeon 2 IMU sensor that measures orientation.
1060 */
1062{
1063private:
1065
1066public:
1067 /**
1068 * \brief The configuration class for this device.
1069 */
1071
1072 /**
1073 * Constructs a new Pigeon 2 sensor object.
1074 *
1075 * \param deviceId ID of the device, as configured in Phoenix Tuner
1076 * \param canbus The CAN bus this device is on
1077 */
1078 CorePigeon2(int deviceId, CANBus canbus);
1079
1080 /**
1081 * \brief Constructs a stubbed-out CorePigeon2, where all status signals, controls,
1082 * configs, etc. perform no action and immediately return OK. This can be used to
1083 * silence error messages for devices that have been completely removed from the robot.
1084 *
1085 * \returns Stubbed-out CorePigeon2
1086 */
1088 {
1089 return CorePigeon2{-1, CANBus{}};
1090 }
1091
1092 /**
1093 * \brief Gets the configurator for this Pigeon2
1094 *
1095 * \details Gets the configurator for this Pigeon2
1096 *
1097 * \returns Configurator for this Pigeon2
1098 */
1100 {
1101 return _configs;
1102 }
1103
1104 /**
1105 * \brief Gets the configurator for this Pigeon2
1106 *
1107 * \details Gets the configurator for this Pigeon2
1108 *
1109 * \returns Configurator for this Pigeon2
1110 */
1112 {
1113 return _configs;
1114 }
1115
1116
1117private:
1118 std::unique_ptr<sim::Pigeon2SimState> _simState{};
1119public:
1120 /**
1121 * \brief Get the simulation state for this device.
1122 *
1123 * \details This function reuses an allocated simulation
1124 * state object, so it is safe to call this function multiple
1125 * times in a robot loop.
1126 *
1127 * \returns Simulation state
1128 */
1130 {
1131 if (_simState == nullptr)
1132 _simState = std::make_unique<sim::Pigeon2SimState>(*this);
1133 return *_simState;
1134 }
1135
1136
1137
1138 /**
1139 * \brief App Major Version number.
1140 *
1141 * - Minimum Value: 0
1142 * - Maximum Value: 255
1143 * - Default Value: 0
1144 * - Units:
1145 *
1146 * Default Rates:
1147 * - CAN: 4.0 Hz
1148 *
1149 * This refreshes and returns a cached StatusSignal object.
1150 *
1151 * \param refresh Whether to refresh the StatusSignal before returning it;
1152 * defaults to true
1153 * \returns VersionMajor Status Signal Object
1154 */
1155 StatusSignal<int> &GetVersionMajor(bool refresh = true);
1156
1157 /**
1158 * \brief App Minor Version number.
1159 *
1160 * - Minimum Value: 0
1161 * - Maximum Value: 255
1162 * - Default Value: 0
1163 * - Units:
1164 *
1165 * Default Rates:
1166 * - CAN: 4.0 Hz
1167 *
1168 * This refreshes and returns a cached StatusSignal object.
1169 *
1170 * \param refresh Whether to refresh the StatusSignal before returning it;
1171 * defaults to true
1172 * \returns VersionMinor Status Signal Object
1173 */
1174 StatusSignal<int> &GetVersionMinor(bool refresh = true);
1175
1176 /**
1177 * \brief App Bugfix Version number.
1178 *
1179 * - Minimum Value: 0
1180 * - Maximum Value: 255
1181 * - Default Value: 0
1182 * - Units:
1183 *
1184 * Default Rates:
1185 * - CAN: 4.0 Hz
1186 *
1187 * This refreshes and returns a cached StatusSignal object.
1188 *
1189 * \param refresh Whether to refresh the StatusSignal before returning it;
1190 * defaults to true
1191 * \returns VersionBugfix Status Signal Object
1192 */
1194
1195 /**
1196 * \brief App Build Version number.
1197 *
1198 * - Minimum Value: 0
1199 * - Maximum Value: 255
1200 * - Default Value: 0
1201 * - Units:
1202 *
1203 * Default Rates:
1204 * - CAN: 4.0 Hz
1205 *
1206 * This refreshes and returns a cached StatusSignal object.
1207 *
1208 * \param refresh Whether to refresh the StatusSignal before returning it;
1209 * defaults to true
1210 * \returns VersionBuild Status Signal Object
1211 */
1212 StatusSignal<int> &GetVersionBuild(bool refresh = true);
1213
1214 /**
1215 * \brief Full Version of firmware in device. The format is a four
1216 * byte value.
1217 *
1218 * - Minimum Value: 0
1219 * - Maximum Value: 4294967295
1220 * - Default Value: 0
1221 * - Units:
1222 *
1223 * Default Rates:
1224 * - CAN: 4.0 Hz
1225 *
1226 * This refreshes and returns a cached StatusSignal object.
1227 *
1228 * \param refresh Whether to refresh the StatusSignal before returning it;
1229 * defaults to true
1230 * \returns Version Status Signal Object
1231 */
1232 StatusSignal<int> &GetVersion(bool refresh = true);
1233
1234 /**
1235 * \brief Integer representing all fault flags reported by the device.
1236 *
1237 * \details These are device specific and are not used directly in
1238 * typical applications. Use the signal specific GetFault_*() methods
1239 * instead.
1240 *
1241 * - Minimum Value: 0
1242 * - Maximum Value: 4294967295
1243 * - Default Value: 0
1244 * - Units:
1245 *
1246 * Default Rates:
1247 * - CAN: 4.0 Hz
1248 *
1249 * This refreshes and returns a cached StatusSignal object.
1250 *
1251 * \param refresh Whether to refresh the StatusSignal before returning it;
1252 * defaults to true
1253 * \returns FaultField Status Signal Object
1254 */
1255 StatusSignal<int> &GetFaultField(bool refresh = true);
1256
1257 /**
1258 * \brief Integer representing all (persistent) sticky fault flags
1259 * reported by the device.
1260 *
1261 * \details These are device specific and are not used directly in
1262 * typical applications. Use the signal specific GetStickyFault_*()
1263 * methods instead.
1264 *
1265 * - Minimum Value: 0
1266 * - Maximum Value: 4294967295
1267 * - Default Value: 0
1268 * - Units:
1269 *
1270 * Default Rates:
1271 * - CAN: 4.0 Hz
1272 *
1273 * This refreshes and returns a cached StatusSignal object.
1274 *
1275 * \param refresh Whether to refresh the StatusSignal before returning it;
1276 * defaults to true
1277 * \returns StickyFaultField Status Signal Object
1278 */
1280
1281 /**
1282 * \brief Current reported yaw of the Pigeon2.
1283 *
1284 * - Minimum Value: -368640.0
1285 * - Maximum Value: 368639.99725341797
1286 * - Default Value: 0
1287 * - Units: deg
1288 *
1289 * Default Rates:
1290 * - CAN 2.0: 100.0 Hz
1291 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1292 *
1293 * This refreshes and returns a cached StatusSignal object.
1294 *
1295 * \param refresh Whether to refresh the StatusSignal before returning it;
1296 * defaults to true
1297 * \returns Yaw Status Signal Object
1298 */
1300
1301 /**
1302 * \brief Current reported pitch of the Pigeon2.
1303 *
1304 * - Minimum Value: -90.0
1305 * - Maximum Value: 89.9560546875
1306 * - Default Value: 0
1307 * - Units: deg
1308 *
1309 * Default Rates:
1310 * - CAN 2.0: 100.0 Hz
1311 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1312 *
1313 * This refreshes and returns a cached StatusSignal object.
1314 *
1315 * \param refresh Whether to refresh the StatusSignal before returning it;
1316 * defaults to true
1317 * \returns Pitch Status Signal Object
1318 */
1320
1321 /**
1322 * \brief Current reported roll of the Pigeon2.
1323 *
1324 * - Minimum Value: -180.0
1325 * - Maximum Value: 179.9560546875
1326 * - Default Value: 0
1327 * - Units: deg
1328 *
1329 * Default Rates:
1330 * - CAN 2.0: 100.0 Hz
1331 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1332 *
1333 * This refreshes and returns a cached StatusSignal object.
1334 *
1335 * \param refresh Whether to refresh the StatusSignal before returning it;
1336 * defaults to true
1337 * \returns Roll Status Signal Object
1338 */
1340
1341 /**
1342 * \brief The W component of the reported Quaternion.
1343 *
1344 * - Minimum Value: -1.0001220852154804
1345 * - Maximum Value: 1.0
1346 * - Default Value: 0
1347 * - Units:
1348 *
1349 * Default Rates:
1350 * - CAN 2.0: 50.0 Hz
1351 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1352 *
1353 * This refreshes and returns a cached StatusSignal object.
1354 *
1355 * \param refresh Whether to refresh the StatusSignal before returning it;
1356 * defaults to true
1357 * \returns QuatW Status Signal Object
1358 */
1360
1361 /**
1362 * \brief The X component of the reported Quaternion.
1363 *
1364 * - Minimum Value: -1.0001220852154804
1365 * - Maximum Value: 1.0
1366 * - Default Value: 0
1367 * - Units:
1368 *
1369 * Default Rates:
1370 * - CAN 2.0: 50.0 Hz
1371 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1372 *
1373 * This refreshes and returns a cached StatusSignal object.
1374 *
1375 * \param refresh Whether to refresh the StatusSignal before returning it;
1376 * defaults to true
1377 * \returns QuatX Status Signal Object
1378 */
1380
1381 /**
1382 * \brief The Y component of the reported Quaternion.
1383 *
1384 * - Minimum Value: -1.0001220852154804
1385 * - Maximum Value: 1.0
1386 * - Default Value: 0
1387 * - Units:
1388 *
1389 * Default Rates:
1390 * - CAN 2.0: 50.0 Hz
1391 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1392 *
1393 * This refreshes and returns a cached StatusSignal object.
1394 *
1395 * \param refresh Whether to refresh the StatusSignal before returning it;
1396 * defaults to true
1397 * \returns QuatY Status Signal Object
1398 */
1400
1401 /**
1402 * \brief The Z component of the reported Quaternion.
1403 *
1404 * - Minimum Value: -1.0001220852154804
1405 * - Maximum Value: 1.0
1406 * - Default Value: 0
1407 * - Units:
1408 *
1409 * Default Rates:
1410 * - CAN 2.0: 50.0 Hz
1411 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1412 *
1413 * This refreshes and returns a cached StatusSignal object.
1414 *
1415 * \param refresh Whether to refresh the StatusSignal before returning it;
1416 * defaults to true
1417 * \returns QuatZ Status Signal Object
1418 */
1420
1421 /**
1422 * \brief The X component of the gravity vector.
1423 *
1424 * \details This is the X component of the reported gravity-vector.
1425 * The gravity vector is not the acceleration experienced by the
1426 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1427 * can be used for mechanisms that are linearly related to gravity,
1428 * such as an arm pivoting about a point, as the contribution of
1429 * gravity to the arm is directly proportional to the contribution of
1430 * gravity about one of these primary axis.
1431 *
1432 * - Minimum Value: -1.000030518509476
1433 * - Maximum Value: 1.0
1434 * - Default Value: 0
1435 * - Units:
1436 *
1437 * Default Rates:
1438 * - CAN 2.0: 10.0 Hz
1439 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1440 *
1441 * This refreshes and returns a cached StatusSignal object.
1442 *
1443 * \param refresh Whether to refresh the StatusSignal before returning it;
1444 * defaults to true
1445 * \returns GravityVectorX Status Signal Object
1446 */
1448
1449 /**
1450 * \brief The Y component of the gravity vector.
1451 *
1452 * \details This is the X component of the reported gravity-vector.
1453 * The gravity vector is not the acceleration experienced by the
1454 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1455 * can be used for mechanisms that are linearly related to gravity,
1456 * such as an arm pivoting about a point, as the contribution of
1457 * gravity to the arm is directly proportional to the contribution of
1458 * gravity about one of these primary axis.
1459 *
1460 * - Minimum Value: -1.000030518509476
1461 * - Maximum Value: 1.0
1462 * - Default Value: 0
1463 * - Units:
1464 *
1465 * Default Rates:
1466 * - CAN 2.0: 10.0 Hz
1467 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1468 *
1469 * This refreshes and returns a cached StatusSignal object.
1470 *
1471 * \param refresh Whether to refresh the StatusSignal before returning it;
1472 * defaults to true
1473 * \returns GravityVectorY Status Signal Object
1474 */
1476
1477 /**
1478 * \brief The Z component of the gravity vector.
1479 *
1480 * \details This is the Z component of the reported gravity-vector.
1481 * The gravity vector is not the acceleration experienced by the
1482 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1483 * can be used for mechanisms that are linearly related to gravity,
1484 * such as an arm pivoting about a point, as the contribution of
1485 * gravity to the arm is directly proportional to the contribution of
1486 * gravity about one of these primary axis.
1487 *
1488 * - Minimum Value: -1.000030518509476
1489 * - Maximum Value: 1.0
1490 * - Default Value: 0
1491 * - Units:
1492 *
1493 * Default Rates:
1494 * - CAN 2.0: 10.0 Hz
1495 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1496 *
1497 * This refreshes and returns a cached StatusSignal object.
1498 *
1499 * \param refresh Whether to refresh the StatusSignal before returning it;
1500 * defaults to true
1501 * \returns GravityVectorZ Status Signal Object
1502 */
1504
1505 /**
1506 * \brief Temperature of the Pigeon 2.
1507 *
1508 * - Minimum Value: -128.0
1509 * - Maximum Value: 127.99609375
1510 * - Default Value: 0
1511 * - Units: ℃
1512 *
1513 * Default Rates:
1514 * - CAN 2.0: 4.0 Hz
1515 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1516 *
1517 * This refreshes and returns a cached StatusSignal object.
1518 *
1519 * \param refresh Whether to refresh the StatusSignal before returning it;
1520 * defaults to true
1521 * \returns Temperature Status Signal Object
1522 */
1524
1525 /**
1526 * \brief Whether the no-motion calibration feature is enabled.
1527 *
1528 * - Default Value: 0
1529 *
1530 * Default Rates:
1531 * - CAN 2.0: 4.0 Hz
1532 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1533 *
1534 * This refreshes and returns a cached StatusSignal object.
1535 *
1536 * \param refresh Whether to refresh the StatusSignal before returning it;
1537 * defaults to true
1538 * \returns NoMotionEnabled Status Signal Object
1539 */
1541
1542 /**
1543 * \brief The number of times a no-motion event occurred, wraps at 15.
1544 *
1545 * - Minimum Value: 0
1546 * - Maximum Value: 15
1547 * - Default Value: 0
1548 * - Units:
1549 *
1550 * Default Rates:
1551 * - CAN 2.0: 4.0 Hz
1552 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1553 *
1554 * This refreshes and returns a cached StatusSignal object.
1555 *
1556 * \param refresh Whether to refresh the StatusSignal before returning it;
1557 * defaults to true
1558 * \returns NoMotionCount Status Signal Object
1559 */
1561
1562 /**
1563 * \brief Whether the temperature-compensation feature is disabled.
1564 *
1565 * - Default Value: 0
1566 *
1567 * Default Rates:
1568 * - CAN 2.0: 4.0 Hz
1569 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1570 *
1571 * This refreshes and returns a cached StatusSignal object.
1572 *
1573 * \param refresh Whether to refresh the StatusSignal before returning it;
1574 * defaults to true
1575 * \returns TemperatureCompensationDisabled Status Signal Object
1576 */
1578
1579 /**
1580 * \brief How long the Pigeon 2's been up in seconds, caps at 255
1581 * seconds.
1582 *
1583 * - Minimum Value: 0
1584 * - Maximum Value: 255
1585 * - Default Value: 0
1586 * - Units: s
1587 *
1588 * Default Rates:
1589 * - CAN 2.0: 4.0 Hz
1590 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1591 *
1592 * This refreshes and returns a cached StatusSignal object.
1593 *
1594 * \param refresh Whether to refresh the StatusSignal before returning it;
1595 * defaults to true
1596 * \returns UpTime Status Signal Object
1597 */
1599
1600 /**
1601 * \brief The accumulated gyro about the X axis without any sensor
1602 * fusing.
1603 *
1604 * - Minimum Value: -23040.0
1605 * - Maximum Value: 23039.9560546875
1606 * - Default Value: 0
1607 * - Units: deg
1608 *
1609 * Default Rates:
1610 * - CAN 2.0: 4.0 Hz
1611 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1612 *
1613 * This refreshes and returns a cached StatusSignal object.
1614 *
1615 * \param refresh Whether to refresh the StatusSignal before returning it;
1616 * defaults to true
1617 * \returns AccumGyroX Status Signal Object
1618 */
1620
1621 /**
1622 * \brief The accumulated gyro about the Y axis without any sensor
1623 * fusing.
1624 *
1625 * - Minimum Value: -23040.0
1626 * - Maximum Value: 23039.9560546875
1627 * - Default Value: 0
1628 * - Units: deg
1629 *
1630 * Default Rates:
1631 * - CAN 2.0: 4.0 Hz
1632 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1633 *
1634 * This refreshes and returns a cached StatusSignal object.
1635 *
1636 * \param refresh Whether to refresh the StatusSignal before returning it;
1637 * defaults to true
1638 * \returns AccumGyroY Status Signal Object
1639 */
1641
1642 /**
1643 * \brief The accumulated gyro about the Z axis without any sensor
1644 * fusing.
1645 *
1646 * - Minimum Value: -23040.0
1647 * - Maximum Value: 23039.9560546875
1648 * - Default Value: 0
1649 * - Units: deg
1650 *
1651 * Default Rates:
1652 * - CAN 2.0: 4.0 Hz
1653 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1654 *
1655 * This refreshes and returns a cached StatusSignal object.
1656 *
1657 * \param refresh Whether to refresh the StatusSignal before returning it;
1658 * defaults to true
1659 * \returns AccumGyroZ Status Signal Object
1660 */
1662
1663 /**
1664 * \brief The angular velocity (ω) of the Pigeon 2 about the X axis
1665 * with respect to the world frame. This value is mount-calibrated.
1666 *
1667 * - Minimum Value: -2048.0
1668 * - Maximum Value: 2047.99609375
1669 * - Default Value: 0
1670 * - Units: dps
1671 *
1672 * Default Rates:
1673 * - CAN 2.0: 10.0 Hz
1674 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1675 *
1676 * This refreshes and returns a cached StatusSignal object.
1677 *
1678 * \param refresh Whether to refresh the StatusSignal before returning it;
1679 * defaults to true
1680 * \returns AngularVelocityXWorld Status Signal Object
1681 */
1683
1684 /**
1685 * \brief The angular velocity (ω) of the Pigeon 2 about the Y axis
1686 * with respect to the world frame. This value is mount-calibrated.
1687 *
1688 * - Minimum Value: -2048.0
1689 * - Maximum Value: 2047.99609375
1690 * - Default Value: 0
1691 * - Units: dps
1692 *
1693 * Default Rates:
1694 * - CAN 2.0: 10.0 Hz
1695 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1696 *
1697 * This refreshes and returns a cached StatusSignal object.
1698 *
1699 * \param refresh Whether to refresh the StatusSignal before returning it;
1700 * defaults to true
1701 * \returns AngularVelocityYWorld Status Signal Object
1702 */
1704
1705 /**
1706 * \brief The angular velocity (ω) of the Pigeon 2 about the Z axis
1707 * with respect to the world frame. This value is mount-calibrated.
1708 *
1709 * - Minimum Value: -2048.0
1710 * - Maximum Value: 2047.99609375
1711 * - Default Value: 0
1712 * - Units: dps
1713 *
1714 * Default Rates:
1715 * - CAN 2.0: 10.0 Hz
1716 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1717 *
1718 * This refreshes and returns a cached StatusSignal object.
1719 *
1720 * \param refresh Whether to refresh the StatusSignal before returning it;
1721 * defaults to true
1722 * \returns AngularVelocityZWorld Status Signal Object
1723 */
1725
1726 /**
1727 * \brief The acceleration measured by Pigeon2 in the X direction.
1728 *
1729 * \details This value includes the acceleration due to gravity. If
1730 * this is undesirable, get the gravity vector and subtract out the
1731 * contribution in this direction.
1732 *
1733 * - Minimum Value: -2.0
1734 * - Maximum Value: 1.99993896484375
1735 * - Default Value: 0
1736 * - Units: g
1737 *
1738 * Default Rates:
1739 * - CAN 2.0: 10.0 Hz
1740 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1741 *
1742 * This refreshes and returns a cached StatusSignal object.
1743 *
1744 * \param refresh Whether to refresh the StatusSignal before returning it;
1745 * defaults to true
1746 * \returns AccelerationX Status Signal Object
1747 */
1749
1750 /**
1751 * \brief The acceleration measured by Pigeon2 in the Y direction.
1752 *
1753 * \details This value includes the acceleration due to gravity. If
1754 * this is undesirable, get the gravity vector and subtract out the
1755 * contribution in this direction.
1756 *
1757 * - Minimum Value: -2.0
1758 * - Maximum Value: 1.99993896484375
1759 * - Default Value: 0
1760 * - Units: g
1761 *
1762 * Default Rates:
1763 * - CAN 2.0: 10.0 Hz
1764 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1765 *
1766 * This refreshes and returns a cached StatusSignal object.
1767 *
1768 * \param refresh Whether to refresh the StatusSignal before returning it;
1769 * defaults to true
1770 * \returns AccelerationY Status Signal Object
1771 */
1773
1774 /**
1775 * \brief The acceleration measured by Pigeon2 in the Z direction.
1776 *
1777 * \details This value includes the acceleration due to gravity. If
1778 * this is undesirable, get the gravity vector and subtract out the
1779 * contribution in this direction.
1780 *
1781 * - Minimum Value: -2.0
1782 * - Maximum Value: 1.99993896484375
1783 * - Default Value: 0
1784 * - Units: g
1785 *
1786 * Default Rates:
1787 * - CAN 2.0: 10.0 Hz
1788 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1789 *
1790 * This refreshes and returns a cached StatusSignal object.
1791 *
1792 * \param refresh Whether to refresh the StatusSignal before returning it;
1793 * defaults to true
1794 * \returns AccelerationZ Status Signal Object
1795 */
1797
1798 /**
1799 * \brief Measured supply voltage to the Pigeon2.
1800 *
1801 * - Minimum Value: 0.0
1802 * - Maximum Value: 31.99951171875
1803 * - Default Value: 0
1804 * - Units: V
1805 *
1806 * Default Rates:
1807 * - CAN 2.0: 4.0 Hz
1808 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1809 *
1810 * This refreshes and returns a cached StatusSignal object.
1811 *
1812 * \param refresh Whether to refresh the StatusSignal before returning it;
1813 * defaults to true
1814 * \returns SupplyVoltage Status Signal Object
1815 */
1817
1818 /**
1819 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1820 * X axis.
1821 *
1822 * \details This value is not mount-calibrated.
1823 *
1824 * - Minimum Value: -1998.048780487805
1825 * - Maximum Value: 1997.987804878049
1826 * - Default Value: 0
1827 * - Units: dps
1828 *
1829 * Default Rates:
1830 * - CAN: 4.0 Hz
1831 *
1832 * This refreshes and returns a cached StatusSignal object.
1833 *
1834 * \param refresh Whether to refresh the StatusSignal before returning it;
1835 * defaults to true
1836 * \returns AngularVelocityXDevice Status Signal Object
1837 */
1839
1840 /**
1841 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1842 * Y axis.
1843 *
1844 * \details This value is not mount-calibrated.
1845 *
1846 * - Minimum Value: -1998.048780487805
1847 * - Maximum Value: 1997.987804878049
1848 * - Default Value: 0
1849 * - Units: dps
1850 *
1851 * Default Rates:
1852 * - CAN: 4.0 Hz
1853 *
1854 * This refreshes and returns a cached StatusSignal object.
1855 *
1856 * \param refresh Whether to refresh the StatusSignal before returning it;
1857 * defaults to true
1858 * \returns AngularVelocityYDevice Status Signal Object
1859 */
1861
1862 /**
1863 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1864 * Z axis.
1865 *
1866 * \details This value is not mount-calibrated.
1867 *
1868 * - Minimum Value: -1998.048780487805
1869 * - Maximum Value: 1997.987804878049
1870 * - Default Value: 0
1871 * - Units: dps
1872 *
1873 * Default Rates:
1874 * - CAN: 4.0 Hz
1875 *
1876 * This refreshes and returns a cached StatusSignal object.
1877 *
1878 * \param refresh Whether to refresh the StatusSignal before returning it;
1879 * defaults to true
1880 * \returns AngularVelocityZDevice Status Signal Object
1881 */
1883
1884 /**
1885 * \brief The biased magnitude of the magnetic field measured by the
1886 * Pigeon 2 in the X direction. This is only valid after performing a
1887 * magnetometer calibration.
1888 *
1889 * - Minimum Value: -19660.8
1890 * - Maximum Value: 19660.2
1891 * - Default Value: 0
1892 * - Units: uT
1893 *
1894 * Default Rates:
1895 * - CAN: 4.0 Hz
1896 *
1897 * This refreshes and returns a cached StatusSignal object.
1898 *
1899 * \param refresh Whether to refresh the StatusSignal before returning it;
1900 * defaults to true
1901 * \returns MagneticFieldX Status Signal Object
1902 */
1904
1905 /**
1906 * \brief The biased magnitude of the magnetic field measured by the
1907 * Pigeon 2 in the Y direction. This is only valid after performing a
1908 * magnetometer calibration.
1909 *
1910 * - Minimum Value: -19660.8
1911 * - Maximum Value: 19660.2
1912 * - Default Value: 0
1913 * - Units: uT
1914 *
1915 * Default Rates:
1916 * - CAN: 4.0 Hz
1917 *
1918 * This refreshes and returns a cached StatusSignal object.
1919 *
1920 * \param refresh Whether to refresh the StatusSignal before returning it;
1921 * defaults to true
1922 * \returns MagneticFieldY Status Signal Object
1923 */
1925
1926 /**
1927 * \brief The biased magnitude of the magnetic field measured by the
1928 * Pigeon 2 in the Z direction. This is only valid after performing a
1929 * magnetometer calibration.
1930 *
1931 * - Minimum Value: -19660.8
1932 * - Maximum Value: 19660.2
1933 * - Default Value: 0
1934 * - Units: uT
1935 *
1936 * Default Rates:
1937 * - CAN: 4.0 Hz
1938 *
1939 * This refreshes and returns a cached StatusSignal object.
1940 *
1941 * \param refresh Whether to refresh the StatusSignal before returning it;
1942 * defaults to true
1943 * \returns MagneticFieldZ Status Signal Object
1944 */
1946
1947 /**
1948 * \brief The raw magnitude of the magnetic field measured by the
1949 * Pigeon 2 in the X direction. This is only valid after performing a
1950 * magnetometer calibration.
1951 *
1952 * - Minimum Value: -19660.8
1953 * - Maximum Value: 19660.2
1954 * - Default Value: 0
1955 * - Units: uT
1956 *
1957 * Default Rates:
1958 * - CAN: 4.0 Hz
1959 *
1960 * This refreshes and returns a cached StatusSignal object.
1961 *
1962 * \param refresh Whether to refresh the StatusSignal before returning it;
1963 * defaults to true
1964 * \returns RawMagneticFieldX Status Signal Object
1965 */
1967
1968 /**
1969 * \brief The raw magnitude of the magnetic field measured by the
1970 * Pigeon 2 in the Y direction. This is only valid after performing a
1971 * magnetometer calibration.
1972 *
1973 * - Minimum Value: -19660.8
1974 * - Maximum Value: 19660.2
1975 * - Default Value: 0
1976 * - Units: uT
1977 *
1978 * Default Rates:
1979 * - CAN: 4.0 Hz
1980 *
1981 * This refreshes and returns a cached StatusSignal object.
1982 *
1983 * \param refresh Whether to refresh the StatusSignal before returning it;
1984 * defaults to true
1985 * \returns RawMagneticFieldY Status Signal Object
1986 */
1988
1989 /**
1990 * \brief The raw magnitude of the magnetic field measured by the
1991 * Pigeon 2 in the Z direction. This is only valid after performing a
1992 * magnetometer calibration.
1993 *
1994 * - Minimum Value: -19660.8
1995 * - Maximum Value: 19660.2
1996 * - Default Value: 0
1997 * - Units: uT
1998 *
1999 * Default Rates:
2000 * - CAN: 4.0 Hz
2001 *
2002 * This refreshes and returns a cached StatusSignal object.
2003 *
2004 * \param refresh Whether to refresh the StatusSignal before returning it;
2005 * defaults to true
2006 * \returns RawMagneticFieldZ Status Signal Object
2007 */
2009
2010 /**
2011 * \brief Whether the device is Phoenix Pro licensed.
2012 *
2013 * - Default Value: False
2014 *
2015 * Default Rates:
2016 * - CAN: 4.0 Hz
2017 *
2018 * This refreshes and returns a cached StatusSignal object.
2019 *
2020 * \param refresh Whether to refresh the StatusSignal before returning it;
2021 * defaults to true
2022 * \returns IsProLicensed Status Signal Object
2023 */
2025
2026 /**
2027 * \brief Hardware fault occurred
2028 *
2029 * - Default Value: False
2030 *
2031 * Default Rates:
2032 * - CAN: 4.0 Hz
2033 *
2034 * This refreshes and returns a cached StatusSignal object.
2035 *
2036 * \param refresh Whether to refresh the StatusSignal before returning it;
2037 * defaults to true
2038 * \returns Fault_Hardware Status Signal Object
2039 */
2041
2042 /**
2043 * \brief Hardware fault occurred
2044 *
2045 * - Default Value: False
2046 *
2047 * Default Rates:
2048 * - CAN: 4.0 Hz
2049 *
2050 * This refreshes and returns a cached StatusSignal object.
2051 *
2052 * \param refresh Whether to refresh the StatusSignal before returning it;
2053 * defaults to true
2054 * \returns StickyFault_Hardware Status Signal Object
2055 */
2057
2058 /**
2059 * \brief Device supply voltage dropped to near brownout levels
2060 *
2061 * - Default Value: False
2062 *
2063 * Default Rates:
2064 * - CAN: 4.0 Hz
2065 *
2066 * This refreshes and returns a cached StatusSignal object.
2067 *
2068 * \param refresh Whether to refresh the StatusSignal before returning it;
2069 * defaults to true
2070 * \returns Fault_Undervoltage Status Signal Object
2071 */
2073
2074 /**
2075 * \brief Device supply voltage dropped to near brownout levels
2076 *
2077 * - Default Value: False
2078 *
2079 * Default Rates:
2080 * - CAN: 4.0 Hz
2081 *
2082 * This refreshes and returns a cached StatusSignal object.
2083 *
2084 * \param refresh Whether to refresh the StatusSignal before returning it;
2085 * defaults to true
2086 * \returns StickyFault_Undervoltage Status Signal Object
2087 */
2089
2090 /**
2091 * \brief Device boot while detecting the enable signal
2092 *
2093 * - Default Value: False
2094 *
2095 * Default Rates:
2096 * - CAN: 4.0 Hz
2097 *
2098 * This refreshes and returns a cached StatusSignal object.
2099 *
2100 * \param refresh Whether to refresh the StatusSignal before returning it;
2101 * defaults to true
2102 * \returns Fault_BootDuringEnable Status Signal Object
2103 */
2105
2106 /**
2107 * \brief Device boot while detecting the enable signal
2108 *
2109 * - Default Value: False
2110 *
2111 * Default Rates:
2112 * - CAN: 4.0 Hz
2113 *
2114 * This refreshes and returns a cached StatusSignal object.
2115 *
2116 * \param refresh Whether to refresh the StatusSignal before returning it;
2117 * defaults to true
2118 * \returns StickyFault_BootDuringEnable Status Signal Object
2119 */
2121
2122 /**
2123 * \brief An unlicensed feature is in use, device may not behave as
2124 * expected.
2125 *
2126 * - Default Value: False
2127 *
2128 * Default Rates:
2129 * - CAN: 4.0 Hz
2130 *
2131 * This refreshes and returns a cached StatusSignal object.
2132 *
2133 * \param refresh Whether to refresh the StatusSignal before returning it;
2134 * defaults to true
2135 * \returns Fault_UnlicensedFeatureInUse Status Signal Object
2136 */
2138
2139 /**
2140 * \brief An unlicensed feature is in use, device may not behave as
2141 * expected.
2142 *
2143 * - Default Value: False
2144 *
2145 * Default Rates:
2146 * - CAN: 4.0 Hz
2147 *
2148 * This refreshes and returns a cached StatusSignal object.
2149 *
2150 * \param refresh Whether to refresh the StatusSignal before returning it;
2151 * defaults to true
2152 * \returns StickyFault_UnlicensedFeatureInUse Status Signal Object
2153 */
2155
2156 /**
2157 * \brief Bootup checks failed: Accelerometer
2158 *
2159 * - Default Value: False
2160 *
2161 * Default Rates:
2162 * - CAN: 4.0 Hz
2163 *
2164 * This refreshes and returns a cached StatusSignal object.
2165 *
2166 * \param refresh Whether to refresh the StatusSignal before returning it;
2167 * defaults to true
2168 * \returns Fault_BootupAccelerometer Status Signal Object
2169 */
2171
2172 /**
2173 * \brief Bootup checks failed: Accelerometer
2174 *
2175 * - Default Value: False
2176 *
2177 * Default Rates:
2178 * - CAN: 4.0 Hz
2179 *
2180 * This refreshes and returns a cached StatusSignal object.
2181 *
2182 * \param refresh Whether to refresh the StatusSignal before returning it;
2183 * defaults to true
2184 * \returns StickyFault_BootupAccelerometer Status Signal Object
2185 */
2187
2188 /**
2189 * \brief Bootup checks failed: Gyroscope
2190 *
2191 * - Default Value: False
2192 *
2193 * Default Rates:
2194 * - CAN: 4.0 Hz
2195 *
2196 * This refreshes and returns a cached StatusSignal object.
2197 *
2198 * \param refresh Whether to refresh the StatusSignal before returning it;
2199 * defaults to true
2200 * \returns Fault_BootupGyroscope Status Signal Object
2201 */
2203
2204 /**
2205 * \brief Bootup checks failed: Gyroscope
2206 *
2207 * - Default Value: False
2208 *
2209 * Default Rates:
2210 * - CAN: 4.0 Hz
2211 *
2212 * This refreshes and returns a cached StatusSignal object.
2213 *
2214 * \param refresh Whether to refresh the StatusSignal before returning it;
2215 * defaults to true
2216 * \returns StickyFault_BootupGyroscope Status Signal Object
2217 */
2219
2220 /**
2221 * \brief Bootup checks failed: Magnetometer
2222 *
2223 * - Default Value: False
2224 *
2225 * Default Rates:
2226 * - CAN: 4.0 Hz
2227 *
2228 * This refreshes and returns a cached StatusSignal object.
2229 *
2230 * \param refresh Whether to refresh the StatusSignal before returning it;
2231 * defaults to true
2232 * \returns Fault_BootupMagnetometer Status Signal Object
2233 */
2235
2236 /**
2237 * \brief Bootup checks failed: Magnetometer
2238 *
2239 * - Default Value: False
2240 *
2241 * Default Rates:
2242 * - CAN: 4.0 Hz
2243 *
2244 * This refreshes and returns a cached StatusSignal object.
2245 *
2246 * \param refresh Whether to refresh the StatusSignal before returning it;
2247 * defaults to true
2248 * \returns StickyFault_BootupMagnetometer Status Signal Object
2249 */
2251
2252 /**
2253 * \brief Motion Detected during bootup.
2254 *
2255 * - Default Value: False
2256 *
2257 * Default Rates:
2258 * - CAN: 4.0 Hz
2259 *
2260 * This refreshes and returns a cached StatusSignal object.
2261 *
2262 * \param refresh Whether to refresh the StatusSignal before returning it;
2263 * defaults to true
2264 * \returns Fault_BootIntoMotion Status Signal Object
2265 */
2267
2268 /**
2269 * \brief Motion Detected during bootup.
2270 *
2271 * - Default Value: False
2272 *
2273 * Default Rates:
2274 * - CAN: 4.0 Hz
2275 *
2276 * This refreshes and returns a cached StatusSignal object.
2277 *
2278 * \param refresh Whether to refresh the StatusSignal before returning it;
2279 * defaults to true
2280 * \returns StickyFault_BootIntoMotion Status Signal Object
2281 */
2283
2284 /**
2285 * \brief Motion stack data acquisition was slower than expected
2286 *
2287 * - Default Value: False
2288 *
2289 * Default Rates:
2290 * - CAN: 4.0 Hz
2291 *
2292 * This refreshes and returns a cached StatusSignal object.
2293 *
2294 * \param refresh Whether to refresh the StatusSignal before returning it;
2295 * defaults to true
2296 * \returns Fault_DataAcquiredLate Status Signal Object
2297 */
2299
2300 /**
2301 * \brief Motion stack data acquisition was slower than expected
2302 *
2303 * - Default Value: False
2304 *
2305 * Default Rates:
2306 * - CAN: 4.0 Hz
2307 *
2308 * This refreshes and returns a cached StatusSignal object.
2309 *
2310 * \param refresh Whether to refresh the StatusSignal before returning it;
2311 * defaults to true
2312 * \returns StickyFault_DataAcquiredLate Status Signal Object
2313 */
2315
2316 /**
2317 * \brief Motion stack loop time was slower than expected.
2318 *
2319 * - Default Value: False
2320 *
2321 * Default Rates:
2322 * - CAN: 4.0 Hz
2323 *
2324 * This refreshes and returns a cached StatusSignal object.
2325 *
2326 * \param refresh Whether to refresh the StatusSignal before returning it;
2327 * defaults to true
2328 * \returns Fault_LoopTimeSlow Status Signal Object
2329 */
2331
2332 /**
2333 * \brief Motion stack loop time was slower than expected.
2334 *
2335 * - Default Value: False
2336 *
2337 * Default Rates:
2338 * - CAN: 4.0 Hz
2339 *
2340 * This refreshes and returns a cached StatusSignal object.
2341 *
2342 * \param refresh Whether to refresh the StatusSignal before returning it;
2343 * defaults to true
2344 * \returns StickyFault_LoopTimeSlow Status Signal Object
2345 */
2347
2348 /**
2349 * \brief Magnetometer values are saturated
2350 *
2351 * - Default Value: False
2352 *
2353 * Default Rates:
2354 * - CAN: 4.0 Hz
2355 *
2356 * This refreshes and returns a cached StatusSignal object.
2357 *
2358 * \param refresh Whether to refresh the StatusSignal before returning it;
2359 * defaults to true
2360 * \returns Fault_SaturatedMagnetometer Status Signal Object
2361 */
2363
2364 /**
2365 * \brief Magnetometer values are saturated
2366 *
2367 * - Default Value: False
2368 *
2369 * Default Rates:
2370 * - CAN: 4.0 Hz
2371 *
2372 * This refreshes and returns a cached StatusSignal object.
2373 *
2374 * \param refresh Whether to refresh the StatusSignal before returning it;
2375 * defaults to true
2376 * \returns StickyFault_SaturatedMagnetometer Status Signal Object
2377 */
2379
2380 /**
2381 * \brief Accelerometer values are saturated
2382 *
2383 * - Default Value: False
2384 *
2385 * Default Rates:
2386 * - CAN: 4.0 Hz
2387 *
2388 * This refreshes and returns a cached StatusSignal object.
2389 *
2390 * \param refresh Whether to refresh the StatusSignal before returning it;
2391 * defaults to true
2392 * \returns Fault_SaturatedAccelerometer Status Signal Object
2393 */
2395
2396 /**
2397 * \brief Accelerometer values are saturated
2398 *
2399 * - Default Value: False
2400 *
2401 * Default Rates:
2402 * - CAN: 4.0 Hz
2403 *
2404 * This refreshes and returns a cached StatusSignal object.
2405 *
2406 * \param refresh Whether to refresh the StatusSignal before returning it;
2407 * defaults to true
2408 * \returns StickyFault_SaturatedAccelerometer Status Signal Object
2409 */
2411
2412 /**
2413 * \brief Gyroscope values are saturated
2414 *
2415 * - Default Value: False
2416 *
2417 * Default Rates:
2418 * - CAN: 4.0 Hz
2419 *
2420 * This refreshes and returns a cached StatusSignal object.
2421 *
2422 * \param refresh Whether to refresh the StatusSignal before returning it;
2423 * defaults to true
2424 * \returns Fault_SaturatedGyroscope Status Signal Object
2425 */
2427
2428 /**
2429 * \brief Gyroscope values are saturated
2430 *
2431 * - Default Value: False
2432 *
2433 * Default Rates:
2434 * - CAN: 4.0 Hz
2435 *
2436 * This refreshes and returns a cached StatusSignal object.
2437 *
2438 * \param refresh Whether to refresh the StatusSignal before returning it;
2439 * defaults to true
2440 * \returns StickyFault_SaturatedGyroscope Status Signal Object
2441 */
2443
2444
2445
2446
2447 /**
2448 * \brief The yaw to set the Pigeon2 to right now.
2449 *
2450 * \param newValue Value to set to. Units are in deg.
2451 * \param timeoutSeconds Maximum time to wait up to in seconds.
2452 * \returns StatusCode of the set command
2453 */
2454 ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue, wpi::units::second_t timeoutSeconds)
2455 {
2456 return GetConfigurator().SetYaw(newValue, timeoutSeconds);
2457 }
2458 /**
2459 * \brief The yaw to set the Pigeon2 to right now.
2460 *
2461 * This will wait up to 0.100 seconds (100ms) by default.
2462 *
2463 * \param newValue Value to set to. Units are in deg.
2464 * \returns StatusCode of the set command
2465 */
2466 ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue)
2467 {
2468 return SetYaw(newValue, 0.100_s);
2469 }
2470
2471 /**
2472 * \brief Clear the sticky faults in the device.
2473 *
2474 * \details This typically has no impact on the device functionality.
2475 * Instead, it just clears telemetry faults that are accessible via
2476 * API and Tuner Self-Test.
2477 *
2478 * \param timeoutSeconds Maximum time to wait up to in seconds.
2479 * \returns StatusCode of the set command
2480 */
2481 ctre::phoenix::StatusCode ClearStickyFaults(wpi::units::second_t timeoutSeconds)
2482 {
2483 return GetConfigurator().ClearStickyFaults(timeoutSeconds);
2484 }
2485 /**
2486 * \brief Clear the sticky faults in the device.
2487 *
2488 * \details This typically has no impact on the device functionality.
2489 * Instead, it just clears telemetry faults that are accessible via
2490 * API and Tuner Self-Test.
2491 *
2492 * This will wait up to 0.100 seconds (100ms) by default.
2493 *
2494 * \returns StatusCode of the set command
2495 */
2500
2501 /**
2502 * \brief Clear sticky fault: Hardware fault occurred
2503 *
2504 * \param timeoutSeconds Maximum time to wait up to in seconds.
2505 * \returns StatusCode of the set command
2506 */
2507 ctre::phoenix::StatusCode ClearStickyFault_Hardware(wpi::units::second_t timeoutSeconds)
2508 {
2509 return GetConfigurator().ClearStickyFault_Hardware(timeoutSeconds);
2510 }
2511 /**
2512 * \brief Clear sticky fault: Hardware fault occurred
2513 *
2514 * This will wait up to 0.100 seconds (100ms) by default.
2515 *
2516 * \returns StatusCode of the set command
2517 */
2522
2523 /**
2524 * \brief Clear sticky fault: Device supply voltage dropped to near
2525 * brownout levels
2526 *
2527 * \param timeoutSeconds Maximum time to wait up to in seconds.
2528 * \returns StatusCode of the set command
2529 */
2531 {
2532 return GetConfigurator().ClearStickyFault_Undervoltage(timeoutSeconds);
2533 }
2534 /**
2535 * \brief Clear sticky fault: Device supply voltage dropped to near
2536 * brownout levels
2537 *
2538 * This will wait up to 0.100 seconds (100ms) by default.
2539 *
2540 * \returns StatusCode of the set command
2541 */
2546
2547 /**
2548 * \brief Clear sticky fault: Device boot while detecting the enable
2549 * signal
2550 *
2551 * \param timeoutSeconds Maximum time to wait up to in seconds.
2552 * \returns StatusCode of the set command
2553 */
2555 {
2556 return GetConfigurator().ClearStickyFault_BootDuringEnable(timeoutSeconds);
2557 }
2558 /**
2559 * \brief Clear sticky fault: Device boot while detecting the enable
2560 * signal
2561 *
2562 * This will wait up to 0.100 seconds (100ms) by default.
2563 *
2564 * \returns StatusCode of the set command
2565 */
2570
2571 /**
2572 * \brief Clear sticky fault: An unlicensed feature is in use, device
2573 * may not behave as expected.
2574 *
2575 * \param timeoutSeconds Maximum time to wait up to in seconds.
2576 * \returns StatusCode of the set command
2577 */
2579 {
2580 return GetConfigurator().ClearStickyFault_UnlicensedFeatureInUse(timeoutSeconds);
2581 }
2582 /**
2583 * \brief Clear sticky fault: An unlicensed feature is in use, device
2584 * may not behave as expected.
2585 *
2586 * This will wait up to 0.100 seconds (100ms) by default.
2587 *
2588 * \returns StatusCode of the set command
2589 */
2594
2595 /**
2596 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2597 *
2598 * \param timeoutSeconds Maximum time to wait up to in seconds.
2599 * \returns StatusCode of the set command
2600 */
2602 {
2603 return GetConfigurator().ClearStickyFault_BootupAccelerometer(timeoutSeconds);
2604 }
2605 /**
2606 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2607 *
2608 * This will wait up to 0.100 seconds (100ms) by default.
2609 *
2610 * \returns StatusCode of the set command
2611 */
2616
2617 /**
2618 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2619 *
2620 * \param timeoutSeconds Maximum time to wait up to in seconds.
2621 * \returns StatusCode of the set command
2622 */
2624 {
2625 return GetConfigurator().ClearStickyFault_BootupGyroscope(timeoutSeconds);
2626 }
2627 /**
2628 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2629 *
2630 * This will wait up to 0.100 seconds (100ms) by default.
2631 *
2632 * \returns StatusCode of the set command
2633 */
2638
2639 /**
2640 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2641 *
2642 * \param timeoutSeconds Maximum time to wait up to in seconds.
2643 * \returns StatusCode of the set command
2644 */
2646 {
2647 return GetConfigurator().ClearStickyFault_BootupMagnetometer(timeoutSeconds);
2648 }
2649 /**
2650 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2651 *
2652 * This will wait up to 0.100 seconds (100ms) by default.
2653 *
2654 * \returns StatusCode of the set command
2655 */
2660
2661 /**
2662 * \brief Clear sticky fault: Motion Detected during bootup.
2663 *
2664 * \param timeoutSeconds Maximum time to wait up to in seconds.
2665 * \returns StatusCode of the set command
2666 */
2668 {
2669 return GetConfigurator().ClearStickyFault_BootIntoMotion(timeoutSeconds);
2670 }
2671 /**
2672 * \brief Clear sticky fault: Motion Detected during bootup.
2673 *
2674 * This will wait up to 0.100 seconds (100ms) by default.
2675 *
2676 * \returns StatusCode of the set command
2677 */
2682
2683 /**
2684 * \brief Clear sticky fault: Motion stack data acquisition was slower
2685 * than expected
2686 *
2687 * \param timeoutSeconds Maximum time to wait up to in seconds.
2688 * \returns StatusCode of the set command
2689 */
2691 {
2692 return GetConfigurator().ClearStickyFault_DataAcquiredLate(timeoutSeconds);
2693 }
2694 /**
2695 * \brief Clear sticky fault: Motion stack data acquisition was slower
2696 * than expected
2697 *
2698 * This will wait up to 0.100 seconds (100ms) by default.
2699 *
2700 * \returns StatusCode of the set command
2701 */
2706
2707 /**
2708 * \brief Clear sticky fault: Motion stack loop time was slower than
2709 * expected.
2710 *
2711 * \param timeoutSeconds Maximum time to wait up to in seconds.
2712 * \returns StatusCode of the set command
2713 */
2715 {
2716 return GetConfigurator().ClearStickyFault_LoopTimeSlow(timeoutSeconds);
2717 }
2718 /**
2719 * \brief Clear sticky fault: Motion stack loop time was slower than
2720 * expected.
2721 *
2722 * This will wait up to 0.100 seconds (100ms) by default.
2723 *
2724 * \returns StatusCode of the set command
2725 */
2730
2731 /**
2732 * \brief Clear sticky fault: Magnetometer values are saturated
2733 *
2734 * \param timeoutSeconds Maximum time to wait up to in seconds.
2735 * \returns StatusCode of the set command
2736 */
2738 {
2739 return GetConfigurator().ClearStickyFault_SaturatedMagnetometer(timeoutSeconds);
2740 }
2741 /**
2742 * \brief Clear sticky fault: Magnetometer values are saturated
2743 *
2744 * This will wait up to 0.100 seconds (100ms) by default.
2745 *
2746 * \returns StatusCode of the set command
2747 */
2752
2753 /**
2754 * \brief Clear sticky fault: Accelerometer values are saturated
2755 *
2756 * \param timeoutSeconds Maximum time to wait up to in seconds.
2757 * \returns StatusCode of the set command
2758 */
2760 {
2761 return GetConfigurator().ClearStickyFault_SaturatedAccelerometer(timeoutSeconds);
2762 }
2763 /**
2764 * \brief Clear sticky fault: Accelerometer values are saturated
2765 *
2766 * This will wait up to 0.100 seconds (100ms) by default.
2767 *
2768 * \returns StatusCode of the set command
2769 */
2774
2775 /**
2776 * \brief Clear sticky fault: Gyroscope values are saturated
2777 *
2778 * \param timeoutSeconds Maximum time to wait up to in seconds.
2779 * \returns StatusCode of the set command
2780 */
2782 {
2783 return GetConfigurator().ClearStickyFault_SaturatedGyroscope(timeoutSeconds);
2784 }
2785 /**
2786 * \brief Clear sticky fault: Gyroscope values are saturated
2787 *
2788 * This will wait up to 0.100 seconds (100ms) by default.
2789 *
2790 * \returns StatusCode of the set command
2791 */
2796};
2797
2798#if defined(_WIN32) || defined(_WIN64)
2799#pragma warning(pop)
2800#endif
2801
2802}
2803}
2804
2805}
2806}
2807
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:563
Custom Params.
Definition CustomParamsConfigs.hpp:23
Configs to trim the Pigeon2's gyroscope.
Definition GyroTrimConfigs.hpp:27
Configs for Pigeon 2's Mount Pose configuration.
Definition MountPoseConfigs.hpp:25
Definition Configuration.hpp:17
ctre::phoenix::StatusCode SetConfigsPrivate(std::string_view serializedString, wpi::units::second_t timeoutSeconds, bool futureProofConfigs, bool overrideIfDuplicate)
wpi::units::second_t DefaultTimeoutSeconds
The default maximum amount of time to wait for a config.
Definition Configurator.hpp:26
ParentConfigurator(hardware::DeviceIdentifier deviceIdentifier)
Definition Configurator.hpp:37
ctre::phoenix::StatusCode GetConfigsPrivate(std::string &serializedString, wpi::units::second_t timeoutSeconds) const
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:712
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs, wpi::units::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:553
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:299
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, wpi::units::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:429
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:998
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs, wpi::units::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:284
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:935
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:839
ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:386
ctre::phoenix::StatusCode ClearStickyFault_Hardware(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse()
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:745
ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue, wpi::units::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs, wpi::units::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:371
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:509
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse(wpi::units::second_t timeoutSeconds)
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:679
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:870
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, wpi::units::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:491
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:270
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:447
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:357
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:967
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs, wpi::units::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:342
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:777
ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:576
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, wpi::units::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:522
ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:540
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs, wpi::units::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:313
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:478
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:1029
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, wpi::units::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:460
ctre::phoenix::StatusCode ClearStickyFaults(wpi::units::second_t timeoutSeconds)
Clear the sticky faults in the device.
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:808
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:612
ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs, wpi::units::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:400
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:415
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:902
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:328
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:647
Configs to enable/disable various features of the Pigeon2.
Definition Pigeon2FeaturesConfigs.hpp:24
The unique identifier for a device.
Definition DeviceIdentifier.hpp:19
ParentDevice(int deviceID, std::string model, CANBus canbus)
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1062
StatusSignal< bool > & GetTemperatureCompensationDisabled(bool refresh=true)
Whether the temperature-compensation feature is disabled.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:2781
static CorePigeon2 None()
Constructs a stubbed-out CorePigeon2, where all status signals, controls, configs,...
Definition CorePigeon2.hpp:1087
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:2542
StatusSignal< wpi::units::scalar_t > & GetQuatX(bool refresh=true)
The X component of the reported Quaternion.
StatusSignal< wpi::units::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< wpi::units::degree_t > & GetRoll(bool refresh=true)
Current reported roll of the Pigeon2.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:2612
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:2759
StatusSignal< wpi::units::degrees_per_second_t > & GetAngularVelocityYDevice(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
StatusSignal< wpi::units::scalar_t > & GetGravityVectorZ(bool refresh=true)
The Z component of the gravity vector.
StatusSignal< bool > & GetFault_SaturatedMagnetometer(bool refresh=true)
Magnetometer values are saturated.
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse()
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:2590
StatusSignal< wpi::units::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_BootupGyroscope(bool refresh=true)
Bootup checks failed: Gyroscope.
StatusSignal< wpi::units::microtesla_t > & GetRawMagneticFieldZ(bool refresh=true)
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
StatusSignal< wpi::units::scalar_t > & GetNoMotionCount(bool refresh=true)
The number of times a no-motion event occurred, wraps at 15.
StatusSignal< bool > & GetFault_LoopTimeSlow(bool refresh=true)
Motion stack loop time was slower than expected.
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.
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2623
StatusSignal< int > & GetVersion(bool refresh=true)
Full Version of firmware in device.
StatusSignal< wpi::units::degree_t > & GetAccumGyroY(bool refresh=true)
The accumulated gyro about the Y axis without any sensor fusing.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:2496
StatusSignal< wpi::units::degree_t > & GetAccumGyroX(bool refresh=true)
The accumulated gyro about the X axis without any sensor fusing.
StatusSignal< wpi::units::microtesla_t > & GetMagneticFieldX(bool refresh=true)
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue, wpi::units::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:2454
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:2702
StatusSignal< bool > & GetStickyFault_SaturatedMagnetometer(bool refresh=true)
Magnetometer values are saturated.
StatusSignal< wpi::units::standard_gravity_t > & GetAccelerationY(bool refresh=true)
The acceleration measured by Pigeon2 in the Y direction.
StatusSignal< bool > & GetStickyFault_BootIntoMotion(bool refresh=true)
Motion Detected during bootup.
StatusSignal< wpi::units::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.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:2770
StatusSignal< int > & GetStickyFaultField(bool refresh=true)
Integer representing all (persistent) sticky fault flags reported by the device.
StatusSignal< wpi::units::scalar_t > & GetQuatW(bool refresh=true)
The W component of the reported Quaternion.
StatusSignal< wpi::units::microtesla_t > & GetRawMagneticFieldY(bool refresh=true)
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
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:2792
configs::Pigeon2Configurator & GetConfigurator()
Gets the configurator for this Pigeon2.
Definition CorePigeon2.hpp:1099
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:2518
ctre::phoenix::StatusCode ClearStickyFaults(wpi::units::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:2481
ctre::phoenix::StatusCode ClearStickyFault_Hardware(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:2507
StatusSignal< bool > & GetStickyFault_Undervoltage(bool refresh=true)
Device supply voltage dropped to near brownout levels.
configs::Pigeon2Configurator const & GetConfigurator() const
Gets the configurator for this Pigeon2.
Definition CorePigeon2.hpp:1111
StatusSignal< bool > & GetFault_BootupGyroscope(bool refresh=true)
Bootup checks failed: Gyroscope.
ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:2466
StatusSignal< wpi::units::scalar_t > & GetQuatY(bool refresh=true)
The Y component of the reported Quaternion.
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2645
StatusSignal< bool > & GetStickyFault_Hardware(bool refresh=true)
Hardware fault occurred.
StatusSignal< bool > & GetStickyFault_SaturatedAccelerometer(bool refresh=true)
Accelerometer values are saturated.
StatusSignal< wpi::units::volt_t > & GetSupplyVoltage(bool refresh=true)
Measured supply voltage to the Pigeon2.
StatusSignal< wpi::units::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.
StatusSignal< wpi::units::second_t > & GetUpTime(bool refresh=true)
How long the Pigeon 2's been up in seconds, caps at 255 seconds.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2737
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2634
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:2678
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2748
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse(wpi::units::second_t timeoutSeconds)
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:2578
StatusSignal< wpi::units::microtesla_t > & GetRawMagneticFieldX(bool refresh=true)
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignal< int > & GetVersionMajor(bool refresh=true)
App Major Version number.
StatusSignal< bool > & GetFault_BootIntoMotion(bool refresh=true)
Motion Detected during bootup.
StatusSignal< wpi::units::standard_gravity_t > & GetAccelerationX(bool refresh=true)
The acceleration measured by Pigeon2 in the X direction.
CorePigeon2(int deviceId, CANBus canbus)
Constructs a new Pigeon 2 sensor object.
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2726
StatusSignal< wpi::units::degree_t > & GetYaw(bool refresh=true)
Current reported yaw of the Pigeon2.
StatusSignal< wpi::units::degrees_per_second_t > & GetAngularVelocityZDevice(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
StatusSignal< bool > & GetStickyFault_SaturatedGyroscope(bool refresh=true)
Gyroscope values are saturated.
StatusSignal< wpi::units::degree_t > & GetAccumGyroZ(bool refresh=true)
The accumulated gyro about the Z axis without any sensor fusing.
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.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:2667
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.
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2714
StatusSignal< wpi::units::standard_gravity_t > & GetAccelerationZ(bool refresh=true)
The acceleration measured by Pigeon2 in the Z direction.
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.
StatusSignal< wpi::units::microtesla_t > & GetMagneticFieldZ(bool refresh=true)
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:2690
StatusSignal< wpi::units::scalar_t > & GetGravityVectorY(bool refresh=true)
The Y component of the gravity vector.
StatusSignal< wpi::units::scalar_t > & GetQuatZ(bool refresh=true)
The Z component of the reported Quaternion.
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.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:2601
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.
StatusSignal< wpi::units::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_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:2566
configs::Pigeon2Configuration Configuration
The configuration class for this device.
Definition CorePigeon2.hpp:1070
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:2554
StatusSignal< int > & GetVersionBuild(bool refresh=true)
App Build Version number.
StatusSignal< wpi::units::scalar_t > & GetGravityVectorX(bool refresh=true)
The X component of the gravity vector.
StatusSignal< wpi::units::celsius_t > & GetTemperature(bool refresh=true)
Temperature of the Pigeon 2.
StatusSignal< wpi::units::degree_t > & GetPitch(bool refresh=true)
Current reported pitch of the Pigeon2.
StatusSignal< bool > & GetStickyFault_BootupAccelerometer(bool refresh=true)
Bootup checks failed: Accelerometer.
StatusSignal< bool > & GetStickyFault_BootupMagnetometer(bool refresh=true)
Bootup checks failed: Magnetometer.
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2656
StatusSignal< bool > & GetStickyFault_DataAcquiredLate(bool refresh=true)
Motion stack data acquisition was slower than expected.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(wpi::units::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:2530
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:1129
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 ExternalFeedbackConfigs.hpp:21
Definition ExternalFeedbackConfigs.hpp:17
Definition ExternalFeedbackConfigs.hpp:17
Definition ExternalFeedbackConfigs.hpp:16
Definition FrcUsageReport.hpp:12
Definition motor_constants.h:14