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