CTRE Phoenix 6 C++ 25.0.0-beta-4
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:
1121 /**
1122 * Constructs a new Pigeon 2 sensor object.
1123 *
1124 * \param deviceId ID of the device, as configured in Phoenix Tuner.
1125 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
1126 * - "rio" for the native roboRIO CAN bus
1127 * - CANivore name or serial number
1128 * - SocketCAN interface (non-FRC Linux only)
1129 * - "*" for any CANivore seen by the program
1130 * - empty string (default) to select the default for the system:
1131 * - "rio" on roboRIO
1132 * - "can0" on Linux
1133 * - "*" on Windows
1134 */
1135 CorePigeon2(int deviceId, std::string canbus = "");
1136
1137 /**
1138 * Constructs a new Pigeon 2 sensor object.
1139 *
1140 * \param deviceId ID of the device, as configured in Phoenix Tuner.
1141 * \param canbus The CAN bus this device is on.
1142 */
1143 CorePigeon2(int deviceId, CANBus canbus) :
1144 CorePigeon2{deviceId, std::string{canbus.GetName()}}
1145 {}
1146
1147 /**
1148 * \brief Gets the configurator for this Pigeon2
1149 *
1150 * \details Gets the configurator for this Pigeon2
1151 *
1152 * \returns Configurator for this Pigeon2
1153 */
1155 {
1156 return _configs;
1157 }
1158
1159 /**
1160 * \brief Gets the configurator for this Pigeon2
1161 *
1162 * \details Gets the configurator for this Pigeon2
1163 *
1164 * \returns Configurator for this Pigeon2
1165 */
1167 {
1168 return _configs;
1169 }
1170
1171
1172private:
1173 std::unique_ptr<sim::Pigeon2SimState> _simState{};
1174public:
1175 /**
1176 * \brief Get the simulation state for this device.
1177 *
1178 * \details This function reuses an allocated simulation
1179 * state object, so it is safe to call this function multiple
1180 * times in a robot loop.
1181 *
1182 * \returns Simulation state
1183 */
1185 {
1186 if (_simState == nullptr)
1187 _simState = std::make_unique<sim::Pigeon2SimState>(*this);
1188 return *_simState;
1189 }
1190
1191
1192
1193 /**
1194 * \brief App Major Version number.
1195 *
1196 * - Minimum Value: 0
1197 * - Maximum Value: 255
1198 * - Default Value: 0
1199 * - Units:
1200 *
1201 * Default Rates:
1202 * - CAN: 4.0 Hz
1203 *
1204 * This refreshes and returns a cached StatusSignal object.
1205 *
1206 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1207 * \returns VersionMajor Status Signal Object
1208 */
1209 StatusSignal<int> &GetVersionMajor(bool refresh = true);
1210
1211 /**
1212 * \brief App Minor Version number.
1213 *
1214 * - Minimum Value: 0
1215 * - Maximum Value: 255
1216 * - Default Value: 0
1217 * - Units:
1218 *
1219 * Default Rates:
1220 * - CAN: 4.0 Hz
1221 *
1222 * This refreshes and returns a cached StatusSignal object.
1223 *
1224 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1225 * \returns VersionMinor Status Signal Object
1226 */
1227 StatusSignal<int> &GetVersionMinor(bool refresh = true);
1228
1229 /**
1230 * \brief App Bugfix Version number.
1231 *
1232 * - Minimum Value: 0
1233 * - Maximum Value: 255
1234 * - Default Value: 0
1235 * - Units:
1236 *
1237 * Default Rates:
1238 * - CAN: 4.0 Hz
1239 *
1240 * This refreshes and returns a cached StatusSignal object.
1241 *
1242 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1243 * \returns VersionBugfix Status Signal Object
1244 */
1246
1247 /**
1248 * \brief App Build Version number.
1249 *
1250 * - Minimum Value: 0
1251 * - Maximum Value: 255
1252 * - Default Value: 0
1253 * - Units:
1254 *
1255 * Default Rates:
1256 * - CAN: 4.0 Hz
1257 *
1258 * This refreshes and returns a cached StatusSignal object.
1259 *
1260 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1261 * \returns VersionBuild Status Signal Object
1262 */
1263 StatusSignal<int> &GetVersionBuild(bool refresh = true);
1264
1265 /**
1266 * \brief Full Version of firmware in device. The format is a four
1267 * byte value.
1268 *
1269 * - Minimum Value: 0
1270 * - Maximum Value: 4294967295
1271 * - Default Value: 0
1272 * - Units:
1273 *
1274 * Default Rates:
1275 * - CAN: 4.0 Hz
1276 *
1277 * This refreshes and returns a cached StatusSignal object.
1278 *
1279 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1280 * \returns Version Status Signal Object
1281 */
1282 StatusSignal<int> &GetVersion(bool refresh = true);
1283
1284 /**
1285 * \brief Integer representing all fault flags reported by the device.
1286 *
1287 * \details These are device specific and are not used directly in
1288 * typical applications. Use the signal specific GetFault_*() methods
1289 * instead.
1290 *
1291 * - Minimum Value: 0
1292 * - Maximum Value: 4294967295
1293 * - Default Value: 0
1294 * - Units:
1295 *
1296 * Default Rates:
1297 * - CAN: 4.0 Hz
1298 *
1299 * This refreshes and returns a cached StatusSignal object.
1300 *
1301 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1302 * \returns FaultField Status Signal Object
1303 */
1304 StatusSignal<int> &GetFaultField(bool refresh = true);
1305
1306 /**
1307 * \brief Integer representing all (persistent) sticky fault flags
1308 * reported by the device.
1309 *
1310 * \details These are device specific and are not used directly in
1311 * typical applications. Use the signal specific GetStickyFault_*()
1312 * methods instead.
1313 *
1314 * - Minimum Value: 0
1315 * - Maximum Value: 4294967295
1316 * - Default Value: 0
1317 * - Units:
1318 *
1319 * Default Rates:
1320 * - CAN: 4.0 Hz
1321 *
1322 * This refreshes and returns a cached StatusSignal object.
1323 *
1324 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1325 * \returns StickyFaultField Status Signal Object
1326 */
1328
1329 /**
1330 * \brief Current reported yaw of the Pigeon2.
1331 *
1332 * - Minimum Value: -368640.0
1333 * - Maximum Value: 368639.99725341797
1334 * - Default Value: 0
1335 * - Units: deg
1336 *
1337 * Default Rates:
1338 * - CAN 2.0: 100.0 Hz
1339 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1340 *
1341 * This refreshes and returns a cached StatusSignal object.
1342 *
1343 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1344 * \returns Yaw Status Signal Object
1345 */
1347
1348 /**
1349 * \brief Current reported pitch of the Pigeon2.
1350 *
1351 * - Minimum Value: -90.0
1352 * - Maximum Value: 89.9560546875
1353 * - Default Value: 0
1354 * - Units: deg
1355 *
1356 * Default Rates:
1357 * - CAN 2.0: 100.0 Hz
1358 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1359 *
1360 * This refreshes and returns a cached StatusSignal object.
1361 *
1362 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1363 * \returns Pitch Status Signal Object
1364 */
1366
1367 /**
1368 * \brief Current reported roll of the Pigeon2.
1369 *
1370 * - Minimum Value: -180.0
1371 * - Maximum Value: 179.9560546875
1372 * - Default Value: 0
1373 * - Units: deg
1374 *
1375 * Default Rates:
1376 * - CAN 2.0: 100.0 Hz
1377 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1378 *
1379 * This refreshes and returns a cached StatusSignal object.
1380 *
1381 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1382 * \returns Roll Status Signal Object
1383 */
1385
1386 /**
1387 * \brief The W component of the reported Quaternion.
1388 *
1389 * - Minimum Value: -1.0001220852154804
1390 * - Maximum Value: 1.0
1391 * - Default Value: 0
1392 * - Units:
1393 *
1394 * Default Rates:
1395 * - CAN 2.0: 50.0 Hz
1396 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1397 *
1398 * This refreshes and returns a cached StatusSignal object.
1399 *
1400 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1401 * \returns QuatW Status Signal Object
1402 */
1404
1405 /**
1406 * \brief The X component of the reported Quaternion.
1407 *
1408 * - Minimum Value: -1.0001220852154804
1409 * - Maximum Value: 1.0
1410 * - Default Value: 0
1411 * - Units:
1412 *
1413 * Default Rates:
1414 * - CAN 2.0: 50.0 Hz
1415 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1416 *
1417 * This refreshes and returns a cached StatusSignal object.
1418 *
1419 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1420 * \returns QuatX Status Signal Object
1421 */
1423
1424 /**
1425 * \brief The Y component of the reported Quaternion.
1426 *
1427 * - Minimum Value: -1.0001220852154804
1428 * - Maximum Value: 1.0
1429 * - Default Value: 0
1430 * - Units:
1431 *
1432 * Default Rates:
1433 * - CAN 2.0: 50.0 Hz
1434 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1435 *
1436 * This refreshes and returns a cached StatusSignal object.
1437 *
1438 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1439 * \returns QuatY Status Signal Object
1440 */
1442
1443 /**
1444 * \brief The Z component of the reported Quaternion.
1445 *
1446 * - Minimum Value: -1.0001220852154804
1447 * - Maximum Value: 1.0
1448 * - Default Value: 0
1449 * - Units:
1450 *
1451 * Default Rates:
1452 * - CAN 2.0: 50.0 Hz
1453 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1454 *
1455 * This refreshes and returns a cached StatusSignal object.
1456 *
1457 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1458 * \returns QuatZ Status Signal Object
1459 */
1461
1462 /**
1463 * \brief The X component of the gravity vector.
1464 *
1465 * \details This is the X component of the reported gravity-vector.
1466 * The gravity vector is not the acceleration experienced by the
1467 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1468 * can be used for mechanisms that are linearly related to gravity,
1469 * such as an arm pivoting about a point, as the contribution of
1470 * gravity to the arm is directly proportional to the contribution of
1471 * gravity about one of these primary axis.
1472 *
1473 * - Minimum Value: -1.000030518509476
1474 * - Maximum Value: 1.0
1475 * - Default Value: 0
1476 * - Units:
1477 *
1478 * Default Rates:
1479 * - CAN 2.0: 10.0 Hz
1480 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1481 *
1482 * This refreshes and returns a cached StatusSignal object.
1483 *
1484 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1485 * \returns GravityVectorX Status Signal Object
1486 */
1488
1489 /**
1490 * \brief The Y component of the gravity vector.
1491 *
1492 * \details This is the X component of the reported gravity-vector.
1493 * The gravity vector is not the acceleration experienced by the
1494 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1495 * can be used for mechanisms that are linearly related to gravity,
1496 * such as an arm pivoting about a point, as the contribution of
1497 * gravity to the arm is directly proportional to the contribution of
1498 * gravity about one of these primary axis.
1499 *
1500 * - Minimum Value: -1.000030518509476
1501 * - Maximum Value: 1.0
1502 * - Default Value: 0
1503 * - Units:
1504 *
1505 * Default Rates:
1506 * - CAN 2.0: 10.0 Hz
1507 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1508 *
1509 * This refreshes and returns a cached StatusSignal object.
1510 *
1511 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1512 * \returns GravityVectorY Status Signal Object
1513 */
1515
1516 /**
1517 * \brief The Z component of the gravity vector.
1518 *
1519 * \details This is the Z component of the reported gravity-vector.
1520 * The gravity vector is not the acceleration experienced by the
1521 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1522 * can be used for mechanisms that are linearly related to gravity,
1523 * such as an arm pivoting about a point, as the contribution of
1524 * gravity to the arm is directly proportional to the contribution of
1525 * gravity about one of these primary axis.
1526 *
1527 * - Minimum Value: -1.000030518509476
1528 * - Maximum Value: 1.0
1529 * - Default Value: 0
1530 * - Units:
1531 *
1532 * Default Rates:
1533 * - CAN 2.0: 10.0 Hz
1534 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1535 *
1536 * This refreshes and returns a cached StatusSignal object.
1537 *
1538 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1539 * \returns GravityVectorZ Status Signal Object
1540 */
1542
1543 /**
1544 * \brief Temperature of the Pigeon 2.
1545 *
1546 * - Minimum Value: -128.0
1547 * - Maximum Value: 127.99609375
1548 * - Default Value: 0
1549 * - Units: ℃
1550 *
1551 * Default Rates:
1552 * - CAN 2.0: 4.0 Hz
1553 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1554 *
1555 * This refreshes and returns a cached StatusSignal object.
1556 *
1557 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1558 * \returns Temperature Status Signal Object
1559 */
1561
1562 /**
1563 * \brief Whether the no-motion calibration feature is enabled.
1564 *
1565 * - Default Value: 0
1566 *
1567 * Default Rates:
1568 * - CAN 2.0: 4.0 Hz
1569 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1570 *
1571 * This refreshes and returns a cached StatusSignal object.
1572 *
1573 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1574 * \returns NoMotionEnabled Status Signal Object
1575 */
1577
1578 /**
1579 * \brief The number of times a no-motion event occurred, wraps at 15.
1580 *
1581 * - Minimum Value: 0
1582 * - Maximum Value: 15
1583 * - Default Value: 0
1584 * - Units:
1585 *
1586 * Default Rates:
1587 * - CAN 2.0: 4.0 Hz
1588 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1589 *
1590 * This refreshes and returns a cached StatusSignal object.
1591 *
1592 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1593 * \returns NoMotionCount Status Signal Object
1594 */
1596
1597 /**
1598 * \brief Whether the temperature-compensation feature is disabled.
1599 *
1600 * - Default Value: 0
1601 *
1602 * Default Rates:
1603 * - CAN 2.0: 4.0 Hz
1604 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1605 *
1606 * This refreshes and returns a cached StatusSignal object.
1607 *
1608 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1609 * \returns TemperatureCompensationDisabled Status Signal Object
1610 */
1612
1613 /**
1614 * \brief How long the Pigeon 2's been up in seconds, caps at 255
1615 * seconds.
1616 *
1617 * - Minimum Value: 0
1618 * - Maximum Value: 255
1619 * - Default Value: 0
1620 * - Units: s
1621 *
1622 * Default Rates:
1623 * - CAN 2.0: 4.0 Hz
1624 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1625 *
1626 * This refreshes and returns a cached StatusSignal object.
1627 *
1628 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1629 * \returns UpTime Status Signal Object
1630 */
1632
1633 /**
1634 * \brief The accumulated gyro about the X axis without any sensor
1635 * fusing.
1636 *
1637 * - Minimum Value: -23040.0
1638 * - Maximum Value: 23039.9560546875
1639 * - Default Value: 0
1640 * - Units: deg
1641 *
1642 * Default Rates:
1643 * - CAN 2.0: 4.0 Hz
1644 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1645 *
1646 * This refreshes and returns a cached StatusSignal object.
1647 *
1648 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1649 * \returns AccumGyroX Status Signal Object
1650 */
1652
1653 /**
1654 * \brief The accumulated gyro about the Y axis without any sensor
1655 * fusing.
1656 *
1657 * - Minimum Value: -23040.0
1658 * - Maximum Value: 23039.9560546875
1659 * - Default Value: 0
1660 * - Units: deg
1661 *
1662 * Default Rates:
1663 * - CAN 2.0: 4.0 Hz
1664 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1665 *
1666 * This refreshes and returns a cached StatusSignal object.
1667 *
1668 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1669 * \returns AccumGyroY Status Signal Object
1670 */
1672
1673 /**
1674 * \brief The accumulated gyro about the Z axis without any sensor
1675 * fusing.
1676 *
1677 * - Minimum Value: -23040.0
1678 * - Maximum Value: 23039.9560546875
1679 * - Default Value: 0
1680 * - Units: deg
1681 *
1682 * Default Rates:
1683 * - CAN 2.0: 4.0 Hz
1684 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1685 *
1686 * This refreshes and returns a cached StatusSignal object.
1687 *
1688 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1689 * \returns AccumGyroZ Status Signal Object
1690 */
1692
1693 /**
1694 * \brief The angular velocity (ω) of the Pigeon 2 about the X axis
1695 * with respect to the world frame. This value is mount-calibrated.
1696 *
1697 * - Minimum Value: -2048.0
1698 * - Maximum Value: 2047.99609375
1699 * - Default Value: 0
1700 * - Units: dps
1701 *
1702 * Default Rates:
1703 * - CAN 2.0: 10.0 Hz
1704 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1705 *
1706 * This refreshes and returns a cached StatusSignal object.
1707 *
1708 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1709 * \returns AngularVelocityXWorld Status Signal Object
1710 */
1712
1713 /**
1714 * \brief The angular velocity (ω) of the Pigeon 2 about the Y axis
1715 * with respect to the world frame. This value is mount-calibrated.
1716 *
1717 * - Minimum Value: -2048.0
1718 * - Maximum Value: 2047.99609375
1719 * - Default Value: 0
1720 * - Units: dps
1721 *
1722 * Default Rates:
1723 * - CAN 2.0: 10.0 Hz
1724 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1725 *
1726 * This refreshes and returns a cached StatusSignal object.
1727 *
1728 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1729 * \returns AngularVelocityYWorld Status Signal Object
1730 */
1732
1733 /**
1734 * \brief The angular velocity (ω) of the Pigeon 2 about the Z axis
1735 * with respect to the world frame. This value is mount-calibrated.
1736 *
1737 * - Minimum Value: -2048.0
1738 * - Maximum Value: 2047.99609375
1739 * - Default Value: 0
1740 * - Units: dps
1741 *
1742 * Default Rates:
1743 * - CAN 2.0: 10.0 Hz
1744 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1745 *
1746 * This refreshes and returns a cached StatusSignal object.
1747 *
1748 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1749 * \returns AngularVelocityZWorld Status Signal Object
1750 */
1752
1753 /**
1754 * \brief The acceleration measured by Pigeon2 in the X direction.
1755 *
1756 * \details This value includes the acceleration due to gravity. If
1757 * this is undesirable, get the gravity vector and subtract out the
1758 * contribution in this direction.
1759 *
1760 * - Minimum Value: -2.0
1761 * - Maximum Value: 1.99993896484375
1762 * - Default Value: 0
1763 * - Units: g
1764 *
1765 * Default Rates:
1766 * - CAN 2.0: 10.0 Hz
1767 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1768 *
1769 * This refreshes and returns a cached StatusSignal object.
1770 *
1771 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1772 * \returns AccelerationX Status Signal Object
1773 */
1775
1776 /**
1777 * \brief The acceleration measured by Pigeon2 in the Y direction.
1778 *
1779 * \details This value includes the acceleration due to gravity. If
1780 * this is undesirable, get the gravity vector and subtract out the
1781 * contribution in this direction.
1782 *
1783 * - Minimum Value: -2.0
1784 * - Maximum Value: 1.99993896484375
1785 * - Default Value: 0
1786 * - Units: g
1787 *
1788 * Default Rates:
1789 * - CAN 2.0: 10.0 Hz
1790 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1791 *
1792 * This refreshes and returns a cached StatusSignal object.
1793 *
1794 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1795 * \returns AccelerationY Status Signal Object
1796 */
1798
1799 /**
1800 * \brief The acceleration measured by Pigeon2 in the Z direction.
1801 *
1802 * \details This value includes the acceleration due to gravity. If
1803 * this is undesirable, get the gravity vector and subtract out the
1804 * contribution in this direction.
1805 *
1806 * - Minimum Value: -2.0
1807 * - Maximum Value: 1.99993896484375
1808 * - Default Value: 0
1809 * - Units: g
1810 *
1811 * Default Rates:
1812 * - CAN 2.0: 10.0 Hz
1813 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1814 *
1815 * This refreshes and returns a cached StatusSignal object.
1816 *
1817 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1818 * \returns AccelerationZ Status Signal Object
1819 */
1821
1822 /**
1823 * \brief Measured supply voltage to the Pigeon2.
1824 *
1825 * - Minimum Value: 0.0
1826 * - Maximum Value: 31.99951171875
1827 * - Default Value: 0
1828 * - Units: V
1829 *
1830 * Default Rates:
1831 * - CAN 2.0: 4.0 Hz
1832 * - CAN FD: 100.0 Hz (TimeSynced with Pro)
1833 *
1834 * This refreshes and returns a cached StatusSignal object.
1835 *
1836 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1837 * \returns SupplyVoltage Status Signal Object
1838 */
1840
1841 /**
1842 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1843 * X axis.
1844 *
1845 * \details This value is not mount-calibrated.
1846 *
1847 * - Minimum Value: -1998.048780487805
1848 * - Maximum Value: 1997.987804878049
1849 * - Default Value: 0
1850 * - Units: dps
1851 *
1852 * Default Rates:
1853 * - CAN: 4.0 Hz
1854 *
1855 * This refreshes and returns a cached StatusSignal object.
1856 *
1857 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1858 * \returns AngularVelocityXDevice Status Signal Object
1859 */
1861
1862 /**
1863 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1864 * Y axis.
1865 *
1866 * \details This value is not mount-calibrated.
1867 *
1868 * - Minimum Value: -1998.048780487805
1869 * - Maximum Value: 1997.987804878049
1870 * - Default Value: 0
1871 * - Units: dps
1872 *
1873 * Default Rates:
1874 * - CAN: 4.0 Hz
1875 *
1876 * This refreshes and returns a cached StatusSignal object.
1877 *
1878 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1879 * \returns AngularVelocityYDevice Status Signal Object
1880 */
1882
1883 /**
1884 * \brief The angular velocity (ω) of the Pigeon 2 about the device's
1885 * Z axis.
1886 *
1887 * \details This value is not mount-calibrated.
1888 *
1889 * - Minimum Value: -1998.048780487805
1890 * - Maximum Value: 1997.987804878049
1891 * - Default Value: 0
1892 * - Units: dps
1893 *
1894 * Default Rates:
1895 * - CAN: 4.0 Hz
1896 *
1897 * This refreshes and returns a cached StatusSignal object.
1898 *
1899 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1900 * \returns AngularVelocityZDevice Status Signal Object
1901 */
1903
1904 /**
1905 * \brief The biased magnitude of the magnetic field measured by the
1906 * Pigeon 2 in the X direction. This is only valid after performing a
1907 * magnetometer calibration.
1908 *
1909 * - Minimum Value: -19660.8
1910 * - Maximum Value: 19660.2
1911 * - Default Value: 0
1912 * - Units: uT
1913 *
1914 * Default Rates:
1915 * - CAN: 4.0 Hz
1916 *
1917 * This refreshes and returns a cached StatusSignal object.
1918 *
1919 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1920 * \returns MagneticFieldX Status Signal Object
1921 */
1923
1924 /**
1925 * \brief The biased magnitude of the magnetic field measured by the
1926 * Pigeon 2 in the Y direction. This is only valid after performing a
1927 * magnetometer calibration.
1928 *
1929 * - Minimum Value: -19660.8
1930 * - Maximum Value: 19660.2
1931 * - Default Value: 0
1932 * - Units: uT
1933 *
1934 * Default Rates:
1935 * - CAN: 4.0 Hz
1936 *
1937 * This refreshes and returns a cached StatusSignal object.
1938 *
1939 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1940 * \returns MagneticFieldY Status Signal Object
1941 */
1943
1944 /**
1945 * \brief The biased magnitude of the magnetic field measured by the
1946 * Pigeon 2 in the Z direction. This is only valid after performing a
1947 * magnetometer calibration.
1948 *
1949 * - Minimum Value: -19660.8
1950 * - Maximum Value: 19660.2
1951 * - Default Value: 0
1952 * - Units: uT
1953 *
1954 * Default Rates:
1955 * - CAN: 4.0 Hz
1956 *
1957 * This refreshes and returns a cached StatusSignal object.
1958 *
1959 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1960 * \returns MagneticFieldZ Status Signal Object
1961 */
1963
1964 /**
1965 * \brief The raw magnitude of the magnetic field measured by the
1966 * Pigeon 2 in the X direction. This is only valid after performing a
1967 * magnetometer calibration.
1968 *
1969 * - Minimum Value: -19660.8
1970 * - Maximum Value: 19660.2
1971 * - Default Value: 0
1972 * - Units: uT
1973 *
1974 * Default Rates:
1975 * - CAN: 4.0 Hz
1976 *
1977 * This refreshes and returns a cached StatusSignal object.
1978 *
1979 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1980 * \returns RawMagneticFieldX Status Signal Object
1981 */
1983
1984 /**
1985 * \brief The raw magnitude of the magnetic field measured by the
1986 * Pigeon 2 in the Y direction. This is only valid after performing a
1987 * magnetometer calibration.
1988 *
1989 * - Minimum Value: -19660.8
1990 * - Maximum Value: 19660.2
1991 * - Default Value: 0
1992 * - Units: uT
1993 *
1994 * Default Rates:
1995 * - CAN: 4.0 Hz
1996 *
1997 * This refreshes and returns a cached StatusSignal object.
1998 *
1999 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2000 * \returns RawMagneticFieldY Status Signal Object
2001 */
2003
2004 /**
2005 * \brief The raw magnitude of the magnetic field measured by the
2006 * Pigeon 2 in the Z direction. This is only valid after performing a
2007 * magnetometer calibration.
2008 *
2009 * - Minimum Value: -19660.8
2010 * - Maximum Value: 19660.2
2011 * - Default Value: 0
2012 * - Units: uT
2013 *
2014 * Default Rates:
2015 * - CAN: 4.0 Hz
2016 *
2017 * This refreshes and returns a cached StatusSignal object.
2018 *
2019 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2020 * \returns RawMagneticFieldZ Status Signal Object
2021 */
2023
2024 /**
2025 * \brief Whether the device is Phoenix Pro licensed.
2026 *
2027 * - Default Value: False
2028 *
2029 * Default Rates:
2030 * - CAN: 4.0 Hz
2031 *
2032 * This refreshes and returns a cached StatusSignal object.
2033 *
2034 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2035 * \returns IsProLicensed Status Signal Object
2036 */
2038
2039 /**
2040 * \brief Hardware fault occurred
2041 *
2042 * - Default Value: False
2043 *
2044 * Default Rates:
2045 * - CAN: 4.0 Hz
2046 *
2047 * This refreshes and returns a cached StatusSignal object.
2048 *
2049 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2050 * \returns Fault_Hardware Status Signal Object
2051 */
2053
2054 /**
2055 * \brief Hardware fault occurred
2056 *
2057 * - Default Value: False
2058 *
2059 * Default Rates:
2060 * - CAN: 4.0 Hz
2061 *
2062 * This refreshes and returns a cached StatusSignal object.
2063 *
2064 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2065 * \returns StickyFault_Hardware Status Signal Object
2066 */
2068
2069 /**
2070 * \brief Device supply voltage dropped to near brownout levels
2071 *
2072 * - Default Value: False
2073 *
2074 * Default Rates:
2075 * - CAN: 4.0 Hz
2076 *
2077 * This refreshes and returns a cached StatusSignal object.
2078 *
2079 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2080 * \returns Fault_Undervoltage Status Signal Object
2081 */
2083
2084 /**
2085 * \brief Device supply voltage dropped to near brownout levels
2086 *
2087 * - Default Value: False
2088 *
2089 * Default Rates:
2090 * - CAN: 4.0 Hz
2091 *
2092 * This refreshes and returns a cached StatusSignal object.
2093 *
2094 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2095 * \returns StickyFault_Undervoltage Status Signal Object
2096 */
2098
2099 /**
2100 * \brief Device boot while detecting the enable signal
2101 *
2102 * - Default Value: False
2103 *
2104 * Default Rates:
2105 * - CAN: 4.0 Hz
2106 *
2107 * This refreshes and returns a cached StatusSignal object.
2108 *
2109 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2110 * \returns Fault_BootDuringEnable Status Signal Object
2111 */
2113
2114 /**
2115 * \brief Device boot while detecting the enable signal
2116 *
2117 * - Default Value: False
2118 *
2119 * Default Rates:
2120 * - CAN: 4.0 Hz
2121 *
2122 * This refreshes and returns a cached StatusSignal object.
2123 *
2124 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2125 * \returns StickyFault_BootDuringEnable Status Signal Object
2126 */
2128
2129 /**
2130 * \brief An unlicensed feature is in use, device may not behave as
2131 * expected.
2132 *
2133 * - Default Value: False
2134 *
2135 * Default Rates:
2136 * - CAN: 4.0 Hz
2137 *
2138 * This refreshes and returns a cached StatusSignal object.
2139 *
2140 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2141 * \returns Fault_UnlicensedFeatureInUse Status Signal Object
2142 */
2144
2145 /**
2146 * \brief An unlicensed feature is in use, device may not behave as
2147 * expected.
2148 *
2149 * - Default Value: False
2150 *
2151 * Default Rates:
2152 * - CAN: 4.0 Hz
2153 *
2154 * This refreshes and returns a cached StatusSignal object.
2155 *
2156 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2157 * \returns StickyFault_UnlicensedFeatureInUse Status Signal Object
2158 */
2160
2161 /**
2162 * \brief Bootup checks failed: Accelerometer
2163 *
2164 * - Default Value: False
2165 *
2166 * Default Rates:
2167 * - CAN: 4.0 Hz
2168 *
2169 * This refreshes and returns a cached StatusSignal object.
2170 *
2171 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2172 * \returns Fault_BootupAccelerometer Status Signal Object
2173 */
2175
2176 /**
2177 * \brief Bootup checks failed: Accelerometer
2178 *
2179 * - Default Value: False
2180 *
2181 * Default Rates:
2182 * - CAN: 4.0 Hz
2183 *
2184 * This refreshes and returns a cached StatusSignal object.
2185 *
2186 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2187 * \returns StickyFault_BootupAccelerometer Status Signal Object
2188 */
2190
2191 /**
2192 * \brief Bootup checks failed: Gyroscope
2193 *
2194 * - Default Value: False
2195 *
2196 * Default Rates:
2197 * - CAN: 4.0 Hz
2198 *
2199 * This refreshes and returns a cached StatusSignal object.
2200 *
2201 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2202 * \returns Fault_BootupGyroscope Status Signal Object
2203 */
2205
2206 /**
2207 * \brief Bootup checks failed: Gyroscope
2208 *
2209 * - Default Value: False
2210 *
2211 * Default Rates:
2212 * - CAN: 4.0 Hz
2213 *
2214 * This refreshes and returns a cached StatusSignal object.
2215 *
2216 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2217 * \returns StickyFault_BootupGyroscope Status Signal Object
2218 */
2220
2221 /**
2222 * \brief Bootup checks failed: Magnetometer
2223 *
2224 * - Default Value: False
2225 *
2226 * Default Rates:
2227 * - CAN: 4.0 Hz
2228 *
2229 * This refreshes and returns a cached StatusSignal object.
2230 *
2231 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2232 * \returns Fault_BootupMagnetometer Status Signal Object
2233 */
2235
2236 /**
2237 * \brief Bootup checks failed: Magnetometer
2238 *
2239 * - Default Value: False
2240 *
2241 * Default Rates:
2242 * - CAN: 4.0 Hz
2243 *
2244 * This refreshes and returns a cached StatusSignal object.
2245 *
2246 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2247 * \returns StickyFault_BootupMagnetometer Status Signal Object
2248 */
2250
2251 /**
2252 * \brief Motion Detected during bootup.
2253 *
2254 * - Default Value: False
2255 *
2256 * Default Rates:
2257 * - CAN: 4.0 Hz
2258 *
2259 * This refreshes and returns a cached StatusSignal object.
2260 *
2261 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2262 * \returns Fault_BootIntoMotion Status Signal Object
2263 */
2265
2266 /**
2267 * \brief Motion Detected during bootup.
2268 *
2269 * - Default Value: False
2270 *
2271 * Default Rates:
2272 * - CAN: 4.0 Hz
2273 *
2274 * This refreshes and returns a cached StatusSignal object.
2275 *
2276 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2277 * \returns StickyFault_BootIntoMotion Status Signal Object
2278 */
2280
2281 /**
2282 * \brief Motion stack data acquisition was slower than expected
2283 *
2284 * - Default Value: False
2285 *
2286 * Default Rates:
2287 * - CAN: 4.0 Hz
2288 *
2289 * This refreshes and returns a cached StatusSignal object.
2290 *
2291 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2292 * \returns Fault_DataAcquiredLate Status Signal Object
2293 */
2295
2296 /**
2297 * \brief Motion stack data acquisition was slower than expected
2298 *
2299 * - Default Value: False
2300 *
2301 * Default Rates:
2302 * - CAN: 4.0 Hz
2303 *
2304 * This refreshes and returns a cached StatusSignal object.
2305 *
2306 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2307 * \returns StickyFault_DataAcquiredLate Status Signal Object
2308 */
2310
2311 /**
2312 * \brief Motion stack loop time was slower than expected.
2313 *
2314 * - Default Value: False
2315 *
2316 * Default Rates:
2317 * - CAN: 4.0 Hz
2318 *
2319 * This refreshes and returns a cached StatusSignal object.
2320 *
2321 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2322 * \returns Fault_LoopTimeSlow Status Signal Object
2323 */
2325
2326 /**
2327 * \brief Motion stack loop time was slower than expected.
2328 *
2329 * - Default Value: False
2330 *
2331 * Default Rates:
2332 * - CAN: 4.0 Hz
2333 *
2334 * This refreshes and returns a cached StatusSignal object.
2335 *
2336 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2337 * \returns StickyFault_LoopTimeSlow Status Signal Object
2338 */
2340
2341 /**
2342 * \brief Magnetometer values are saturated
2343 *
2344 * - Default Value: False
2345 *
2346 * Default Rates:
2347 * - CAN: 4.0 Hz
2348 *
2349 * This refreshes and returns a cached StatusSignal object.
2350 *
2351 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2352 * \returns Fault_SaturatedMagnetometer Status Signal Object
2353 */
2355
2356 /**
2357 * \brief Magnetometer values are saturated
2358 *
2359 * - Default Value: False
2360 *
2361 * Default Rates:
2362 * - CAN: 4.0 Hz
2363 *
2364 * This refreshes and returns a cached StatusSignal object.
2365 *
2366 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2367 * \returns StickyFault_SaturatedMagnetometer Status Signal Object
2368 */
2370
2371 /**
2372 * \brief Accelerometer values are saturated
2373 *
2374 * - Default Value: False
2375 *
2376 * Default Rates:
2377 * - CAN: 4.0 Hz
2378 *
2379 * This refreshes and returns a cached StatusSignal object.
2380 *
2381 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2382 * \returns Fault_SaturatedAccelerometer Status Signal Object
2383 */
2385
2386 /**
2387 * \brief Accelerometer values are saturated
2388 *
2389 * - Default Value: False
2390 *
2391 * Default Rates:
2392 * - CAN: 4.0 Hz
2393 *
2394 * This refreshes and returns a cached StatusSignal object.
2395 *
2396 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2397 * \returns StickyFault_SaturatedAccelerometer Status Signal Object
2398 */
2400
2401 /**
2402 * \brief Gyroscope values are saturated
2403 *
2404 * - Default Value: False
2405 *
2406 * Default Rates:
2407 * - CAN: 4.0 Hz
2408 *
2409 * This refreshes and returns a cached StatusSignal object.
2410 *
2411 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2412 * \returns Fault_SaturatedGyroscope Status Signal Object
2413 */
2415
2416 /**
2417 * \brief Gyroscope values are saturated
2418 *
2419 * - Default Value: False
2420 *
2421 * Default Rates:
2422 * - CAN: 4.0 Hz
2423 *
2424 * This refreshes and returns a cached StatusSignal object.
2425 *
2426 * \param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2427 * \returns StickyFault_SaturatedGyroscope Status Signal Object
2428 */
2430
2431
2432
2433 /**
2434 * \brief Control device with generic control request object. User must make
2435 * sure the specified object is castable to a valid control request,
2436 * otherwise this function will fail at run-time and return the NotSupported
2437 * StatusCode
2438 *
2439 * \param request Control object to request of the device
2440 * \returns Status Code of the request, 0 is OK
2441 */
2443 {
2444 controls::ControlRequest const *ptr = &request;
2445 (void)ptr;
2446
2448 }
2449
2450
2451 /**
2452 * \brief The yaw to set the Pigeon2 to right now.
2453 *
2454 * \param newValue Value to set to. Units are in deg.
2455 * \param timeoutSeconds Maximum time to wait up to in seconds.
2456 * \returns StatusCode of the set command
2457 */
2458 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
2459 {
2460 return GetConfigurator().SetYaw(newValue, timeoutSeconds);
2461 }
2462 /**
2463 * \brief The yaw to set the Pigeon2 to right now.
2464 *
2465 * This will wait up to 0.100 seconds (100ms) by default.
2466 *
2467 * \param newValue Value to set to. Units are in deg.
2468 * \returns StatusCode of the set command
2469 */
2470 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
2471 {
2472 return SetYaw(newValue, 0.100_s);
2473 }
2474
2475 /**
2476 * \brief Clear the sticky faults in the device.
2477 *
2478 * \details This typically has no impact on the device functionality.
2479 * Instead, it just clears telemetry faults that are accessible via
2480 * API and Tuner Self-Test.
2481 *
2482 * \param timeoutSeconds Maximum time to wait up to in seconds.
2483 * \returns StatusCode of the set command
2484 */
2485 ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
2486 {
2487 return GetConfigurator().ClearStickyFaults(timeoutSeconds);
2488 }
2489 /**
2490 * \brief Clear the sticky faults in the device.
2491 *
2492 * \details This typically has no impact on the device functionality.
2493 * Instead, it just clears telemetry faults that are accessible via
2494 * API and Tuner Self-Test.
2495 *
2496 * This will wait up to 0.100 seconds (100ms) by default.
2497 *
2498 * \returns StatusCode of the set command
2499 */
2504
2505 /**
2506 * \brief Clear sticky fault: Hardware fault occurred
2507 *
2508 * \param timeoutSeconds Maximum time to wait up to in seconds.
2509 * \returns StatusCode of the set command
2510 */
2511 ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
2512 {
2513 return GetConfigurator().ClearStickyFault_Hardware(timeoutSeconds);
2514 }
2515 /**
2516 * \brief Clear sticky fault: Hardware fault occurred
2517 *
2518 * This will wait up to 0.100 seconds (100ms) by default.
2519 *
2520 * \returns StatusCode of the set command
2521 */
2526
2527 /**
2528 * \brief Clear sticky fault: Device supply voltage dropped to near
2529 * brownout levels
2530 *
2531 * \param timeoutSeconds Maximum time to wait up to in seconds.
2532 * \returns StatusCode of the set command
2533 */
2534 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
2535 {
2536 return GetConfigurator().ClearStickyFault_Undervoltage(timeoutSeconds);
2537 }
2538 /**
2539 * \brief Clear sticky fault: Device supply voltage dropped to near
2540 * brownout levels
2541 *
2542 * This will wait up to 0.100 seconds (100ms) by default.
2543 *
2544 * \returns StatusCode of the set command
2545 */
2550
2551 /**
2552 * \brief Clear sticky fault: Device boot while detecting the enable
2553 * signal
2554 *
2555 * \param timeoutSeconds Maximum time to wait up to in seconds.
2556 * \returns StatusCode of the set command
2557 */
2559 {
2560 return GetConfigurator().ClearStickyFault_BootDuringEnable(timeoutSeconds);
2561 }
2562 /**
2563 * \brief Clear sticky fault: Device boot while detecting the enable
2564 * signal
2565 *
2566 * This will wait up to 0.100 seconds (100ms) by default.
2567 *
2568 * \returns StatusCode of the set command
2569 */
2574
2575 /**
2576 * \brief Clear sticky fault: An unlicensed feature is in use, device
2577 * may not behave as expected.
2578 *
2579 * \param timeoutSeconds Maximum time to wait up to in seconds.
2580 * \returns StatusCode of the set command
2581 */
2583 {
2585 }
2586 /**
2587 * \brief Clear sticky fault: An unlicensed feature is in use, device
2588 * may not behave as expected.
2589 *
2590 * This will wait up to 0.100 seconds (100ms) by default.
2591 *
2592 * \returns StatusCode of the set command
2593 */
2598
2599 /**
2600 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2601 *
2602 * \param timeoutSeconds Maximum time to wait up to in seconds.
2603 * \returns StatusCode of the set command
2604 */
2606 {
2608 }
2609 /**
2610 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2611 *
2612 * This will wait up to 0.100 seconds (100ms) by default.
2613 *
2614 * \returns StatusCode of the set command
2615 */
2620
2621 /**
2622 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2623 *
2624 * \param timeoutSeconds Maximum time to wait up to in seconds.
2625 * \returns StatusCode of the set command
2626 */
2628 {
2629 return GetConfigurator().ClearStickyFault_BootupGyroscope(timeoutSeconds);
2630 }
2631 /**
2632 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2633 *
2634 * This will wait up to 0.100 seconds (100ms) by default.
2635 *
2636 * \returns StatusCode of the set command
2637 */
2642
2643 /**
2644 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2645 *
2646 * \param timeoutSeconds Maximum time to wait up to in seconds.
2647 * \returns StatusCode of the set command
2648 */
2650 {
2652 }
2653 /**
2654 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2655 *
2656 * This will wait up to 0.100 seconds (100ms) by default.
2657 *
2658 * \returns StatusCode of the set command
2659 */
2664
2665 /**
2666 * \brief Clear sticky fault: Motion Detected during bootup.
2667 *
2668 * \param timeoutSeconds Maximum time to wait up to in seconds.
2669 * \returns StatusCode of the set command
2670 */
2672 {
2673 return GetConfigurator().ClearStickyFault_BootIntoMotion(timeoutSeconds);
2674 }
2675 /**
2676 * \brief Clear sticky fault: Motion Detected during bootup.
2677 *
2678 * This will wait up to 0.100 seconds (100ms) by default.
2679 *
2680 * \returns StatusCode of the set command
2681 */
2686
2687 /**
2688 * \brief Clear sticky fault: Motion stack data acquisition was slower
2689 * than expected
2690 *
2691 * \param timeoutSeconds Maximum time to wait up to in seconds.
2692 * \returns StatusCode of the set command
2693 */
2695 {
2696 return GetConfigurator().ClearStickyFault_DataAcquiredLate(timeoutSeconds);
2697 }
2698 /**
2699 * \brief Clear sticky fault: Motion stack data acquisition was slower
2700 * than expected
2701 *
2702 * This will wait up to 0.100 seconds (100ms) by default.
2703 *
2704 * \returns StatusCode of the set command
2705 */
2710
2711 /**
2712 * \brief Clear sticky fault: Motion stack loop time was slower than
2713 * expected.
2714 *
2715 * \param timeoutSeconds Maximum time to wait up to in seconds.
2716 * \returns StatusCode of the set command
2717 */
2718 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
2719 {
2720 return GetConfigurator().ClearStickyFault_LoopTimeSlow(timeoutSeconds);
2721 }
2722 /**
2723 * \brief Clear sticky fault: Motion stack loop time was slower than
2724 * expected.
2725 *
2726 * This will wait up to 0.100 seconds (100ms) by default.
2727 *
2728 * \returns StatusCode of the set command
2729 */
2734
2735 /**
2736 * \brief Clear sticky fault: Magnetometer values are saturated
2737 *
2738 * \param timeoutSeconds Maximum time to wait up to in seconds.
2739 * \returns StatusCode of the set command
2740 */
2742 {
2744 }
2745 /**
2746 * \brief Clear sticky fault: Magnetometer values are saturated
2747 *
2748 * This will wait up to 0.100 seconds (100ms) by default.
2749 *
2750 * \returns StatusCode of the set command
2751 */
2756
2757 /**
2758 * \brief Clear sticky fault: Accelerometer values are saturated
2759 *
2760 * \param timeoutSeconds Maximum time to wait up to in seconds.
2761 * \returns StatusCode of the set command
2762 */
2764 {
2766 }
2767 /**
2768 * \brief Clear sticky fault: Accelerometer values are saturated
2769 *
2770 * This will wait up to 0.100 seconds (100ms) by default.
2771 *
2772 * \returns StatusCode of the set command
2773 */
2778
2779 /**
2780 * \brief Clear sticky fault: Gyroscope values are saturated
2781 *
2782 * \param timeoutSeconds Maximum time to wait up to in seconds.
2783 * \returns StatusCode of the set command
2784 */
2786 {
2788 }
2789 /**
2790 * \brief Clear sticky fault: Gyroscope values are saturated
2791 *
2792 * This will wait up to 0.100 seconds (100ms) by default.
2793 *
2794 * \returns StatusCode of the set command
2795 */
2800};
2801
2802}
2803}
2804
2805}
2806}
2807
ii that the Software will be uninterrupted or error free
Definition CTRE_LICENSE.txt:226
CTREXPORT int c_ctre_phoenix6_serialize_double(int spn, double value, char **str)
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Represents a status signal with data of type T, and operations available to retrieve information abou...
Definition StatusSignal.hpp:657
Custom Params.
Definition Configs.hpp:3640
std::string ToString() const override
Definition Configs.hpp:3709
std::string Serialize() const override
Definition Configs.hpp:3718
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3727
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:29
Definition DeviceIdentifier.hpp:19
Parent class for all devices.
Definition ParentDevice.hpp:29
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp: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:2546
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2649
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:2616
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:2694
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse()
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:2594
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:2500
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2718
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:2706
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:2774
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:2796
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:1154
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:2522
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:2458
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:1166
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:2785
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:2485
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2741
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2638
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:2682
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2752
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:2558
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:1143
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2730
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:2534
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2627
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:2671
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:2582
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:2511
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:2470
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:2570
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:2605
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:2442
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:2763
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2660
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:1184
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 StatusCodes.h:18
Definition span.hpp:401