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