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