CTRE Phoenix Pro C++ 23.0.12
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
12
14#include <units/acceleration.h>
15#include <units/angle.h>
16#include <units/angular_velocity.h>
17#include <units/dimensionless.h>
18#include <units/magnetic_field_strength.h>
19#include <units/temperature.h>
20#include <units/time.h>
21#include <units/voltage.h>
22
23namespace ctre {
24namespace phoenixpro {
25
26namespace hardware {
27namespace core {
28 class CorePigeon2;
29}
30}
31
32namespace configs {
33
34/**
35 * Class description for the Pigeon 2 IMU sensor that measures orientation.
36 *
37 * This handles the configurations for the hardware#Pigeon2
38 */
40{
41public:
42 /**
43 * \brief True if we should factory default newer unsupported configs,
44 * false to leave newer unsupported configs alone.
45 *
46 * \details This flag addresses a corner case where the device may have
47 * firmware with newer configs that didn't exist when this
48 * version of the API was built. If this occurs and this
49 * flag is true, unsupported new configs will be factory
50 * defaulted to avoid unexpected behavior.
51 *
52 * This is also the behavior in Phoenix 5, so this flag
53 * is defaulted to true to match.
54 */
56
57
58 /**
59 * \brief Configs for Pigeon 2's Mount Pose configuration.
60 *
61 * \details These configs allow the Pigeon2 to be mounted in whatever
62 * orientation that's desired and ensure the reported
63 * Yaw/Pitch/Roll is from the robot's reference.
64 */
66
67 /**
68 * \brief Configs to trim the Pigeon2's gyroscope.
69 *
70 * \details Pigeon2 allows the user to trim the gyroscope's
71 * sensitivity. While this isn't necessary for the Pigeon2,
72 * as it comes calibrated out-of-the-box, users can make use
73 * of this to make the Pigeon2 even more accurate for their
74 * application.
75 */
77
78 /**
79 * \brief Configs to enable/disable various features of the Pigeon2.
80 *
81 * \details These configs allow the user to enable or disable various
82 * aspects of the Pigeon2.
83 */
85
86 /**
87 * \brief Get the string representation of this configuration
88 */
89 std::string ToString() const
90 {
91 std::stringstream ss;
92 ss << MountPose.ToString();
93 ss << GyroTrim.ToString();
95 return ss.str();
96 }
97
98 /**
99 * \brief Get the serialized form of this configuration
100 */
101 std::string Serialize() const
102 {
103 std::stringstream ss;
104 ss << MountPose.Serialize();
105 ss << GyroTrim.Serialize();
107 return ss.str();
108 }
109
110 /**
111 * \brief Take a string and deserialize it to this configuration
112 */
113 ctre::phoenix::StatusCode Deserialize(const std::string& string)
114 {
115 ctre::phoenix::StatusCode err = ctre::phoenix::StatusCode::OK;
116 err = MountPose.Deserialize(string);
117 err = GyroTrim.Deserialize(string);
118 err = Pigeon2Features.Deserialize(string);
119 return err;
120 }
121};
122
123/**
124 * Class description for the Pigeon 2 IMU sensor that measures orientation.
125 *
126 * This handles the configurations for the hardware#Pigeon2
127 */
129{
131 ParentConfigurator{std::move(id)}
132 {}
133
135public:
136
137 /**
138 * Delete the copy constructor, we can only pass by reference
139 */
141
142 /**
143 * \brief Refreshes the values of the specified config group.
144 *
145 * This will wait up to #defaultTimeoutSeconds.
146 *
147 * \details Call to refresh the selected configs from the device.
148 *
149 * \param configs The configs to refresh
150 * \returns StatusCode of refreshing the configs
151 */
152 ctre::phoenix::StatusCode Refresh(Pigeon2Configuration& configs) const
153 {
154 return Refresh(configs, defaultTimeoutSeconds);
155 }
156
157 /**
158 * \brief Refreshes the values of the specified config group.
159 *
160 * \details Call to refresh the selected configs from the device.
161 *
162 * \param configs The configs to refresh
163 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
164 * \returns StatusCode of refreshing the configs
165 */
166 ctre::phoenix::StatusCode Refresh(Pigeon2Configuration& configs, units::time::second_t timeoutSeconds) const
167 {
168 std::string ref;
169 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
170 configs.Deserialize(ref);
171 return ret;
172 }
173
174 /**
175 * \brief Applies the contents of the specified config to the device.
176 *
177 * This will wait up to #defaultTimeoutSeconds.
178 *
179 * \details Call to apply the selected configs.
180 *
181 * \param configs Configs to apply against.
182 * \returns StatusCode of the set command
183 */
184 ctre::phoenix::StatusCode Apply(const Pigeon2Configuration& configs)
185 {
186 return Apply(configs, defaultTimeoutSeconds);
187 }
188
189 /**
190 * \brief Applies the contents of the specified config to the device.
191 *
192 * \details Call to apply the selected configs.
193 *
194 * \param configs Configs to apply against.
195 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
196 * \returns StatusCode of the set command
197 */
198 ctre::phoenix::StatusCode Apply(const Pigeon2Configuration& configs, units::time::second_t timeoutSeconds)
199 {
200 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, configs.FutureProofConfigs, false);
201 }
202
203
204 /**
205 * \brief Refreshes the values of the specified config group.
206 *
207 * This will wait up to #defaultTimeoutSeconds.
208 *
209 * \details Call to refresh the selected configs from the device.
210 *
211 * \param configs The configs to refresh
212 * \returns StatusCode of refreshing the configs
213 */
214 ctre::phoenix::StatusCode Refresh(MountPoseConfigs& configs) const
215 {
216 return Refresh(configs, defaultTimeoutSeconds);
217 }
218 /**
219 * \brief Refreshes the values of the specified config group.
220 *
221 * \details Call to refresh the selected configs from the device.
222 *
223 * \param configs The configs to refresh
224 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
225 * \returns StatusCode of refreshing the configs
226 */
227 ctre::phoenix::StatusCode Refresh(MountPoseConfigs& configs, units::time::second_t timeoutSeconds) const
228 {
229 std::string ref;
230 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
231 configs.Deserialize(ref);
232 return ret;
233 }
234
235 /**
236 * \brief Applies the contents of the specified config to the device.
237 *
238 * This will wait up to #defaultTimeoutSeconds.
239 *
240 * \details Call to apply the selected configs.
241 *
242 * \param configs Configs to apply against.
243 * \returns StatusCode of the set command
244 */
245 ctre::phoenix::StatusCode Apply(const MountPoseConfigs& configs)
246 {
247 return Apply(configs, defaultTimeoutSeconds);
248 }
249
250 /**
251 * \brief Applies the contents of the specified config to the device.
252 *
253 * \details Call to apply the selected configs.
254 *
255 * \param configs Configs to apply against.
256 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
257 * \returns StatusCode of the set command
258 */
259 ctre::phoenix::StatusCode Apply(const MountPoseConfigs& configs, units::time::second_t timeoutSeconds)
260 {
261 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
262 }
263
264 /**
265 * \brief Refreshes the values of the specified config group.
266 *
267 * This will wait up to #defaultTimeoutSeconds.
268 *
269 * \details Call to refresh the selected configs from the device.
270 *
271 * \param configs The configs to refresh
272 * \returns StatusCode of refreshing the configs
273 */
274 ctre::phoenix::StatusCode Refresh(GyroTrimConfigs& configs) const
275 {
276 return Refresh(configs, defaultTimeoutSeconds);
277 }
278 /**
279 * \brief Refreshes the values of the specified config group.
280 *
281 * \details Call to refresh the selected configs from the device.
282 *
283 * \param configs The configs to refresh
284 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
285 * \returns StatusCode of refreshing the configs
286 */
287 ctre::phoenix::StatusCode Refresh(GyroTrimConfigs& configs, units::time::second_t timeoutSeconds) const
288 {
289 std::string ref;
290 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
291 configs.Deserialize(ref);
292 return ret;
293 }
294
295 /**
296 * \brief Applies the contents of the specified config to the device.
297 *
298 * This will wait up to #defaultTimeoutSeconds.
299 *
300 * \details Call to apply the selected configs.
301 *
302 * \param configs Configs to apply against.
303 * \returns StatusCode of the set command
304 */
305 ctre::phoenix::StatusCode Apply(const GyroTrimConfigs& configs)
306 {
307 return Apply(configs, defaultTimeoutSeconds);
308 }
309
310 /**
311 * \brief Applies the contents of the specified config to the device.
312 *
313 * \details Call to apply the selected configs.
314 *
315 * \param configs Configs to apply against.
316 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
317 * \returns StatusCode of the set command
318 */
319 ctre::phoenix::StatusCode Apply(const GyroTrimConfigs& configs, units::time::second_t timeoutSeconds)
320 {
321 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
322 }
323
324 /**
325 * \brief Refreshes the values of the specified config group.
326 *
327 * This will wait up to #defaultTimeoutSeconds.
328 *
329 * \details Call to refresh the selected configs from the device.
330 *
331 * \param configs The configs to refresh
332 * \returns StatusCode of refreshing the configs
333 */
334 ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs& configs) const
335 {
336 return Refresh(configs, defaultTimeoutSeconds);
337 }
338 /**
339 * \brief Refreshes the values of the specified config group.
340 *
341 * \details Call to refresh the selected configs from the device.
342 *
343 * \param configs The configs to refresh
344 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
345 * \returns StatusCode of refreshing the configs
346 */
347 ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs& configs, units::time::second_t timeoutSeconds) const
348 {
349 std::string ref;
350 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
351 configs.Deserialize(ref);
352 return ret;
353 }
354
355 /**
356 * \brief Applies the contents of the specified config to the device.
357 *
358 * This will wait up to #defaultTimeoutSeconds.
359 *
360 * \details Call to apply the selected configs.
361 *
362 * \param configs Configs to apply against.
363 * \returns StatusCode of the set command
364 */
365 ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs& configs)
366 {
367 return Apply(configs, defaultTimeoutSeconds);
368 }
369
370 /**
371 * \brief Applies the contents of the specified config to the device.
372 *
373 * \details Call to apply the selected configs.
374 *
375 * \param configs Configs to apply against.
376 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
377 * \returns StatusCode of the set command
378 */
379 ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs& configs, units::time::second_t timeoutSeconds)
380 {
381 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
382 }
383
384
385 /**
386 * \brief The yaw to set the Pigeon2 to right now.
387 *
388 * This will wait up to #defaultTimeoutSeconds.
389 *
390 * This is available in the configurator in case the user wants
391 * to initialize their device entirely without passing a device
392 * reference down to the code that performs the initialization.
393 * In this case, the user passes down the configurator object
394 * and performs all the initialization code on the object.
395 *
396 * \param newValue Value to set to.
397 * \returns StatusCode of the set command
398 */
399 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
400 {
401 return SetYaw(newValue, defaultTimeoutSeconds);
402 }
403 /**
404 * \brief The yaw to set the Pigeon2 to right now.
405 *
406 * This is available in the configurator in case the user wants
407 * to initialize their device entirely without passing a device
408 * reference down to the code that performs the initialization.
409 * In this case, the user passes down the configurator object
410 * and performs all the initialization code on the object.
411 *
412 * \param newValue Value to set to.
413 * \param timeoutSeconds Maximum time to wait up to in seconds.
414 * \returns StatusCode of the set command
415 */
416 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
417 {
418 std::stringstream ss;
419 char *ref;
420 c_ctre_phoenixpro_serialize_double(1012, newValue.to<double>(), &ref); if(ref != nullptr) { ss << ref; free(ref); }
421 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
422 }
423
424 /**
425 * \brief Clear the sticky faults in the device.
426 *
427 * \details This typically has no impact on the device functionality.
428 * Instead, it just clears telemetry faults that are accessible via
429 * API and Tuner Self-Test.
430 *
431 * This will wait up to #defaultTimeoutSeconds.
432 *
433 * This is available in the configurator in case the user wants
434 * to initialize their device entirely without passing a device
435 * reference down to the code that performs the initialization.
436 * In this case, the user passes down the configurator object
437 * and performs all the initialization code on the object.
438 * \returns StatusCode of the set command
439 */
440 ctre::phoenix::StatusCode ClearStickyFaults()
441 {
443 }
444 /**
445 * \brief Clear the sticky faults in the device.
446 *
447 * \details This typically has no impact on the device functionality.
448 * Instead, it just clears telemetry faults that are accessible via
449 * API and Tuner Self-Test.
450 *
451 * This is available in the configurator in case the user wants
452 * to initialize their device entirely without passing a device
453 * reference down to the code that performs the initialization.
454 * In this case, the user passes down the configurator object
455 * and performs all the initialization code on the object.
456 * \param timeoutSeconds Maximum time to wait up to in seconds.
457 * \returns StatusCode of the set command
458 */
459 ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
460 {
461 std::stringstream ss;
462 char *ref;
463 c_ctre_phoenixpro_serialize_double(1476, 0, &ref); if(ref != nullptr) { ss << ref; free(ref); }
464 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
465 }
466};
467
468}
469
470namespace hardware {
471namespace core {
472
473/**
474 * Class description for the Pigeon 2 IMU sensor that measures orientation.
475 */
477{
478private:
480
481 bool _isInitialized = false;
482 bool _isVersionOk = false;
484 double _timeToRefreshVersion = GetCurrentTimeSeconds();
485
486 StatusSignalValue<int> &_resetFlags = LookupStatusSignalValue<int>(ctre::phoenixpro::spns::SpnValue::Startup_ResetFlags, "ResetFlags", false);
487 units::time::second_t _resetTimestamp{0_s};
488
489 double _creationTime = GetCurrentTimeSeconds();
490
491 void ReportIfTooOld();
492
493
494public:
495 /**
496 * Constructs a new Pigeon 2 sensor object.
497 *
498 * \param deviceId ID of the device, as configured in Phoenix Tuner.
499 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
500 * - "rio" for the native roboRIO CAN bus
501 * - CANivore name or serial number
502 * - SocketCAN interface (non-FRC Linux only)
503 * - "*" for any CANivore seen by the program
504 * - empty string (default) to select the default for the system:
505 * - "rio" on roboRIO
506 * - "can0" on Linux
507 * - "*" on Windows
508 */
509 CorePigeon2(int deviceId, std::string canbus = "");
510
511 CorePigeon2(CorePigeon2 const &) = delete;
513
514 /**
515 * \returns true if device has reset since the previous call of this routine.
516 */
518
519 /**
520 * \brief Gets the configurator for this Pigeon2
521 *
522 * \details Gets the configurator for this Pigeon2
523 *
524 * \returns Configurator for this Pigeon2
525 */
527 {
528 return _configs;
529 }
530
531 /**
532 * \brief Gets the configurator for this Pigeon2
533 *
534 * \details Gets the configurator for this Pigeon2
535 *
536 * \returns Configurator for this Pigeon2
537 */
539 {
540 return _configs;
541 }
542
543
544private:
545 std::unique_ptr<sim::Pigeon2SimState> _simState{};
546public:
547 /**
548 * \brief Get the simulation state for this device.
549 *
550 * \details This function reuses an allocated simulation
551 * state object, so it is safe to call this function multiple
552 * times in a robot loop.
553 *
554 * \returns Simulation state
555 */
557 {
558 if (_simState == nullptr)
559 _simState = std::make_unique<sim::Pigeon2SimState>(*this);
560 return *_simState;
561 }
562
563
564
565 /**
566 * \brief App Major Version number.
567 *
568 * Minimum Value: 0
569 * Maximum Value: 255
570 * Default Value: 0
571 * Units:
572 *
573 * Default Rates:
574 * CAN: 4.0 Hz
575 *
576 * \returns VersionMajor Status Signal Value object
577 */
579
580 /**
581 * \brief App Minor Version number.
582 *
583 * Minimum Value: 0
584 * Maximum Value: 255
585 * Default Value: 0
586 * Units:
587 *
588 * Default Rates:
589 * CAN: 4.0 Hz
590 *
591 * \returns VersionMinor Status Signal Value object
592 */
594
595 /**
596 * \brief App Bugfix Version number.
597 *
598 * Minimum Value: 0
599 * Maximum Value: 255
600 * Default Value: 0
601 * Units:
602 *
603 * Default Rates:
604 * CAN: 4.0 Hz
605 *
606 * \returns VersionBugfix Status Signal Value object
607 */
609
610 /**
611 * \brief App Build Version number.
612 *
613 * Minimum Value: 0
614 * Maximum Value: 255
615 * Default Value: 0
616 * Units:
617 *
618 * Default Rates:
619 * CAN: 4.0 Hz
620 *
621 * \returns VersionBuild Status Signal Value object
622 */
624
625 /**
626 * \brief Full Version. The format is a four byte value.
627 *
628 * \details Full Version of firmware in device. The format is a four
629 * byte value.
630 *
631 * Minimum Value: 0
632 * Maximum Value: 4294967295
633 * Default Value: 0
634 * Units:
635 *
636 * Default Rates:
637 * CAN: 4.0 Hz
638 *
639 * \returns Version Status Signal Value object
640 */
642
643 /**
644 * \brief Integer representing all faults
645 *
646 * \details This returns the fault flags reported by the device. These
647 * are device specific and are not used directly in typical
648 * applications. Use the signal specific GetFault_*() methods instead.
649 *
650 *
651 * Minimum Value: 0
652 * Maximum Value: 1048575
653 * Default Value: 0
654 * Units:
655 *
656 * Default Rates:
657 * CAN: 4.0 Hz
658 *
659 * \returns FaultField Status Signal Value object
660 */
662
663 /**
664 * \brief Integer representing all sticky faults
665 *
666 * \details This returns the persistent "sticky" fault flags reported
667 * by the device. These are device specific and are not used directly
668 * in typical applications. Use the signal specific GetStickyFault_*()
669 * methods instead.
670 *
671 * Minimum Value: 0
672 * Maximum Value: 1048575
673 * Default Value: 0
674 * Units:
675 *
676 * Default Rates:
677 * CAN: 4.0 Hz
678 *
679 * \returns StickyFaultField Status Signal Value object
680 */
682
683 /**
684 * \brief Current reported yaw of the Pigeon2.
685 *
686 * Minimum Value: -368640.0
687 * Maximum Value: 368639.99725341797
688 * Default Value: 0
689 * Units: deg
690 *
691 * Default Rates:
692 * CAN: 100.0 Hz
693 *
694 * \returns Yaw Status Signal Value object
695 */
697
698 /**
699 * \brief Current reported pitch of the Pigeon2.
700 *
701 * Minimum Value: -90.0
702 * Maximum Value: 89.9560546875
703 * Default Value: 0
704 * Units: deg
705 *
706 * Default Rates:
707 * CAN: 100.0 Hz
708 *
709 * \returns Pitch Status Signal Value object
710 */
712
713 /**
714 * \brief Current reported roll of the Pigeon2.
715 *
716 * Minimum Value: -180.0
717 * Maximum Value: 179.9560546875
718 * Default Value: 0
719 * Units: deg
720 *
721 * Default Rates:
722 * CAN: 100.0 Hz
723 *
724 * \returns Roll Status Signal Value object
725 */
727
728 /**
729 * \brief The W component of the reported Quaternion.
730 *
731 * Minimum Value: -1.0001220852154804
732 * Maximum Value: 1.0
733 * Default Value: 0
734 * Units:
735 *
736 * Default Rates:
737 * CAN 2.0: 50.0 Hz
738 * CAN FD: 100.0 Hz
739 *
740 * \returns QuatW Status Signal Value object
741 */
743
744 /**
745 * \brief The X component of the reported Quaternion.
746 *
747 * Minimum Value: -1.0001220852154804
748 * Maximum Value: 1.0
749 * Default Value: 0
750 * Units:
751 *
752 * Default Rates:
753 * CAN 2.0: 50.0 Hz
754 * CAN FD: 100.0 Hz
755 *
756 * \returns QuatX Status Signal Value object
757 */
759
760 /**
761 * \brief The Y component of the reported Quaternion.
762 *
763 * Minimum Value: -1.0001220852154804
764 * Maximum Value: 1.0
765 * Default Value: 0
766 * Units:
767 *
768 * Default Rates:
769 * CAN 2.0: 50.0 Hz
770 * CAN FD: 100.0 Hz
771 *
772 * \returns QuatY Status Signal Value object
773 */
775
776 /**
777 * \brief The Z component of the reported Quaternion.
778 *
779 * Minimum Value: -1.0001220852154804
780 * Maximum Value: 1.0
781 * Default Value: 0
782 * Units:
783 *
784 * Default Rates:
785 * CAN 2.0: 50.0 Hz
786 * CAN FD: 100.0 Hz
787 *
788 * \returns QuatZ Status Signal Value object
789 */
791
792 /**
793 * \brief The X component of the gravity vector.
794 *
795 * \details This is the X component of the reported gravity-vector.
796 * The gravity vector is not the acceleration experienced by the
797 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
798 * can be used for mechanisms that are linearly related to gravity,
799 * such as an arm pivoting about a point, as the contribution of
800 * gravity to the arm is directly proportional to the contribution of
801 * gravity about one of these primary axis.
802 *
803 * Minimum Value: -1.000030518509476
804 * Maximum Value: 1.0
805 * Default Value: 0
806 * Units:
807 *
808 * Default Rates:
809 * CAN 2.0: 10.0 Hz
810 * CAN FD: 100.0 Hz
811 *
812 * \returns GravityVectorX Status Signal Value object
813 */
815
816 /**
817 * \brief The Y component of the gravity vector.
818 *
819 * \details This is the X component of the reported gravity-vector.
820 * The gravity vector is not the acceleration experienced by the
821 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
822 * can be used for mechanisms that are linearly related to gravity,
823 * such as an arm pivoting about a point, as the contribution of
824 * gravity to the arm is directly proportional to the contribution of
825 * gravity about one of these primary axis.
826 *
827 * Minimum Value: -1.000030518509476
828 * Maximum Value: 1.0
829 * Default Value: 0
830 * Units:
831 *
832 * Default Rates:
833 * CAN 2.0: 10.0 Hz
834 * CAN FD: 100.0 Hz
835 *
836 * \returns GravityVectorY Status Signal Value object
837 */
839
840 /**
841 * \brief The Z component of the gravity vector.
842 *
843 * \details This is the Z component of the reported gravity-vector.
844 * The gravity vector is not the acceleration experienced by the
845 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
846 * can be used for mechanisms that are linearly related to gravity,
847 * such as an arm pivoting about a point, as the contribution of
848 * gravity to the arm is directly proportional to the contribution of
849 * gravity about one of these primary axis.
850 *
851 * Minimum Value: -1.000030518509476
852 * Maximum Value: 1.0
853 * Default Value: 0
854 * Units:
855 *
856 * Default Rates:
857 * CAN 2.0: 10.0 Hz
858 * CAN FD: 100.0 Hz
859 *
860 * \returns GravityVectorZ Status Signal Value object
861 */
863
864 /**
865 * \brief Temperature of the Pigeon 2.
866 *
867 * Minimum Value: -128.0
868 * Maximum Value: 127.99609375
869 * Default Value: 0
870 * Units: ℃
871 *
872 * Default Rates:
873 * CAN 2.0: 10.0 Hz
874 * CAN FD: 100.0 Hz
875 *
876 * \returns Temperature Status Signal Value object
877 */
879
880 /**
881 * \brief Whether the no-motion calibration feature is enabled.
882 *
883 * Default Value: 0
884 *
885 * Default Rates:
886 * CAN 2.0: 10.0 Hz
887 * CAN FD: 100.0 Hz
888 *
889 * \returns NoMotionEnabled Status Signal Value object
890 */
892
893 /**
894 * \brief The number of times a no-motion event occurred, wraps at 15.
895 *
896 * Minimum Value: 0
897 * Maximum Value: 15
898 * Default Value: 0
899 * Units:
900 *
901 * Default Rates:
902 * CAN 2.0: 10.0 Hz
903 * CAN FD: 100.0 Hz
904 *
905 * \returns NoMotionCount Status Signal Value object
906 */
908
909 /**
910 * \brief Whether the temperature-compensation feature is disabled.
911 *
912 * Default Value: 0
913 *
914 * Default Rates:
915 * CAN 2.0: 10.0 Hz
916 * CAN FD: 100.0 Hz
917 *
918 * \returns TemperatureCompensationDisabled Status Signal Value object
919 */
921
922 /**
923 * \brief How long the Pigeon 2's been up in seconds, caps at 255
924 * seconds.
925 *
926 * Minimum Value: 0
927 * Maximum Value: 255
928 * Default Value: 0
929 * Units: s
930 *
931 * Default Rates:
932 * CAN 2.0: 10.0 Hz
933 * CAN FD: 100.0 Hz
934 *
935 * \returns UpTime Status Signal Value object
936 */
938
939 /**
940 * \brief The accumulated gyro about the X axis without any sensor
941 * fusing.
942 *
943 * Minimum Value: -23040.0
944 * Maximum Value: 23039.9560546875
945 * Default Value: 0
946 * Units: deg
947 *
948 * Default Rates:
949 * CAN 2.0: 10.0 Hz
950 * CAN FD: 100.0 Hz
951 *
952 * \returns AccumGyroX Status Signal Value object
953 */
955
956 /**
957 * \brief The accumulated gyro about the Y axis without any sensor
958 * fusing.
959 *
960 * Minimum Value: -23040.0
961 * Maximum Value: 23039.9560546875
962 * Default Value: 0
963 * Units: deg
964 *
965 * Default Rates:
966 * CAN 2.0: 10.0 Hz
967 * CAN FD: 100.0 Hz
968 *
969 * \returns AccumGyroY Status Signal Value object
970 */
972
973 /**
974 * \brief The accumulated gyro about the Z axis without any sensor
975 * fusing.
976 *
977 * Minimum Value: -23040.0
978 * Maximum Value: 23039.9560546875
979 * Default Value: 0
980 * Units: deg
981 *
982 * Default Rates:
983 * CAN 2.0: 10.0 Hz
984 * CAN FD: 100.0 Hz
985 *
986 * \returns AccumGyroZ Status Signal Value object
987 */
989
990 /**
991 * \brief The angular velocity (ω) of the Pigeon 2 about the X axis.
992 *
993 * Minimum Value: -1998.048780487805
994 * Maximum Value: 1997.987804878049
995 * Default Value: 0
996 * Units: dps
997 *
998 * Default Rates:
999 * CAN 2.0: 10.0 Hz
1000 * CAN FD: 100.0 Hz
1001 *
1002 * \returns AngularVelocityX Status Signal Value object
1003 */
1005
1006 /**
1007 * \brief The angular velocity (ω) of the Pigeon 2 about the Y axis.
1008 *
1009 * Minimum Value: -1998.048780487805
1010 * Maximum Value: 1997.987804878049
1011 * Default Value: 0
1012 * Units: dps
1013 *
1014 * Default Rates:
1015 * CAN 2.0: 10.0 Hz
1016 * CAN FD: 100.0 Hz
1017 *
1018 * \returns AngularVelocityY Status Signal Value object
1019 */
1021
1022 /**
1023 * \brief The angular velocity (ω) of the Pigeon 2 about the Z axis.
1024 *
1025 * Minimum Value: -1998.048780487805
1026 * Maximum Value: 1997.987804878049
1027 * Default Value: 0
1028 * Units: dps
1029 *
1030 * Default Rates:
1031 * CAN 2.0: 10.0 Hz
1032 * CAN FD: 100.0 Hz
1033 *
1034 * \returns AngularVelocityZ Status Signal Value object
1035 */
1037
1038 /**
1039 * \brief The acceleration measured by Pigeon2 in the X direction.
1040 *
1041 * \details This value includes the acceleration due to gravity. If
1042 * this is undesirable, get the gravity vector and subtract out the
1043 * contribution in this direction.
1044 *
1045 * Minimum Value: -2.0
1046 * Maximum Value: 1.99993896484375
1047 * Default Value: 0
1048 * Units: g
1049 *
1050 * Default Rates:
1051 * CAN 2.0: 10.0 Hz
1052 * CAN FD: 100.0 Hz
1053 *
1054 * \returns AccelerationX Status Signal Value object
1055 */
1057
1058 /**
1059 * \brief The acceleration measured by Pigeon2 in the Y direction.
1060 *
1061 * \details This value includes the acceleration due to gravity. If
1062 * this is undesirable, get the gravity vector and subtract out the
1063 * contribution in this direction.
1064 *
1065 * Minimum Value: -2.0
1066 * Maximum Value: 1.99993896484375
1067 * Default Value: 0
1068 * Units: g
1069 *
1070 * Default Rates:
1071 * CAN 2.0: 10.0 Hz
1072 * CAN FD: 100.0 Hz
1073 *
1074 * \returns AccelerationY Status Signal Value object
1075 */
1077
1078 /**
1079 * \brief The acceleration measured by Pigeon2 in the Z direction.
1080 *
1081 * \details This value includes the acceleration due to gravity. If
1082 * this is undesirable, get the gravity vector and subtract out the
1083 * contribution in this direction.
1084 *
1085 * Minimum Value: -2.0
1086 * Maximum Value: 1.99993896484375
1087 * Default Value: 0
1088 * Units: g
1089 *
1090 * Default Rates:
1091 * CAN 2.0: 10.0 Hz
1092 * CAN FD: 100.0 Hz
1093 *
1094 * \returns AccelerationZ Status Signal Value object
1095 */
1097
1098 /**
1099 * \brief Measured supply voltage to the Pigeon2.
1100 *
1101 * Minimum Value: 0.0
1102 * Maximum Value: 31.99951171875
1103 * Default Value: 0
1104 * Units: V
1105 *
1106 * Default Rates:
1107 * CAN: 10.0 Hz
1108 *
1109 * \returns SupplyVoltage Status Signal Value object
1110 */
1112
1113 /**
1114 * \brief The biased magnitude of the magnetic field measured by the
1115 * Pigeon 2 in the X direction. This is only valid after performing a
1116 * magnetometer calibration.
1117 *
1118 * Minimum Value: -19660.8
1119 * Maximum Value: 19660.2
1120 * Default Value: 0
1121 * Units: uT
1122 *
1123 * Default Rates:
1124 * CAN: 5.0 Hz
1125 *
1126 * \returns MagneticFieldX Status Signal Value object
1127 */
1129
1130 /**
1131 * \brief The biased magnitude of the magnetic field measured by the
1132 * Pigeon 2 in the Y direction. This is only valid after performing a
1133 * magnetometer calibration.
1134 *
1135 * Minimum Value: -19660.8
1136 * Maximum Value: 19660.2
1137 * Default Value: 0
1138 * Units: uT
1139 *
1140 * Default Rates:
1141 * CAN: 5.0 Hz
1142 *
1143 * \returns MagneticFieldY Status Signal Value object
1144 */
1146
1147 /**
1148 * \brief The biased magnitude of the magnetic field measured by the
1149 * Pigeon 2 in the Z direction. This is only valid after performing a
1150 * magnetometer calibration.
1151 *
1152 * Minimum Value: -19660.8
1153 * Maximum Value: 19660.2
1154 * Default Value: 0
1155 * Units: uT
1156 *
1157 * Default Rates:
1158 * CAN: 5.0 Hz
1159 *
1160 * \returns MagneticFieldZ Status Signal Value object
1161 */
1163
1164 /**
1165 * \brief The raw magnitude of the magnetic field measured by the
1166 * Pigeon 2 in the X direction. This is only valid after performing a
1167 * magnetometer calibration.
1168 *
1169 * Minimum Value: -19660.8
1170 * Maximum Value: 19660.2
1171 * Default Value: 0
1172 * Units: uT
1173 *
1174 * Default Rates:
1175 * CAN: 5.0 Hz
1176 *
1177 * \returns RawMagneticFieldX Status Signal Value object
1178 */
1180
1181 /**
1182 * \brief The raw magnitude of the magnetic field measured by the
1183 * Pigeon 2 in the Y direction. This is only valid after performing a
1184 * magnetometer calibration.
1185 *
1186 * Minimum Value: -19660.8
1187 * Maximum Value: 19660.2
1188 * Default Value: 0
1189 * Units: uT
1190 *
1191 * Default Rates:
1192 * CAN: 5.0 Hz
1193 *
1194 * \returns RawMagneticFieldY Status Signal Value object
1195 */
1197
1198 /**
1199 * \brief The raw magnitude of the magnetic field measured by the
1200 * Pigeon 2 in the Z direction. This is only valid after performing a
1201 * magnetometer calibration.
1202 *
1203 * Minimum Value: -19660.8
1204 * Maximum Value: 19660.2
1205 * Default Value: 0
1206 * Units: uT
1207 *
1208 * Default Rates:
1209 * CAN: 5.0 Hz
1210 *
1211 * \returns RawMagneticFieldZ Status Signal Value object
1212 */
1214
1215 /**
1216 * \brief Hardware fault occurred
1217 *
1218 * Default Value: False
1219 *
1220 * Default Rates:
1221 * CAN: 4.0 Hz
1222 *
1223 * \returns Fault_Hardware Status Signal Value object
1224 */
1226
1227 /**
1228 * \brief Hardware fault occurred
1229 *
1230 * Default Value: False
1231 *
1232 * Default Rates:
1233 * CAN: 4.0 Hz
1234 *
1235 * \returns StickyFault_Hardware Status Signal Value object
1236 */
1238
1239 /**
1240 * \brief Device supply voltage dropped to near brownout levels
1241 *
1242 * Default Value: False
1243 *
1244 * Default Rates:
1245 * CAN: 4.0 Hz
1246 *
1247 * \returns Fault_Undervoltage Status Signal Value object
1248 */
1250
1251 /**
1252 * \brief Device supply voltage dropped to near brownout levels
1253 *
1254 * Default Value: False
1255 *
1256 * Default Rates:
1257 * CAN: 4.0 Hz
1258 *
1259 * \returns StickyFault_Undervoltage Status Signal Value object
1260 */
1262
1263 /**
1264 * \brief Device boot while detecting the enable signal
1265 *
1266 * Default Value: False
1267 *
1268 * Default Rates:
1269 * CAN: 4.0 Hz
1270 *
1271 * \returns Fault_BootDuringEnable Status Signal Value object
1272 */
1274
1275 /**
1276 * \brief Device boot while detecting the enable signal
1277 *
1278 * Default Value: False
1279 *
1280 * Default Rates:
1281 * CAN: 4.0 Hz
1282 *
1283 * \returns StickyFault_BootDuringEnable Status Signal Value object
1284 */
1286
1287 /**
1288 * \brief Bootup checks failed: Accelerometer
1289 *
1290 * Default Value: False
1291 *
1292 * Default Rates:
1293 * CAN: 4.0 Hz
1294 *
1295 * \returns Fault_BootupAccelerometer Status Signal Value object
1296 */
1298
1299 /**
1300 * \brief Bootup checks failed: Accelerometer
1301 *
1302 * Default Value: False
1303 *
1304 * Default Rates:
1305 * CAN: 4.0 Hz
1306 *
1307 * \returns StickyFault_BootupAccelerometer Status Signal Value object
1308 */
1310
1311 /**
1312 * \brief Bootup checks failed: Gyroscope
1313 *
1314 * Default Value: False
1315 *
1316 * Default Rates:
1317 * CAN: 4.0 Hz
1318 *
1319 * \returns Fault_BootupGyroscope Status Signal Value object
1320 */
1322
1323 /**
1324 * \brief Bootup checks failed: Gyroscope
1325 *
1326 * Default Value: False
1327 *
1328 * Default Rates:
1329 * CAN: 4.0 Hz
1330 *
1331 * \returns StickyFault_BootupGyroscope Status Signal Value object
1332 */
1334
1335 /**
1336 * \brief Bootup checks failed: Magnetometer
1337 *
1338 * Default Value: False
1339 *
1340 * Default Rates:
1341 * CAN: 4.0 Hz
1342 *
1343 * \returns Fault_BootupMagnetometer Status Signal Value object
1344 */
1346
1347 /**
1348 * \brief Bootup checks failed: Magnetometer
1349 *
1350 * Default Value: False
1351 *
1352 * Default Rates:
1353 * CAN: 4.0 Hz
1354 *
1355 * \returns StickyFault_BootupMagnetometer Status Signal Value object
1356 */
1358
1359 /**
1360 * \brief Motion Detected during bootup.
1361 *
1362 * Default Value: False
1363 *
1364 * Default Rates:
1365 * CAN: 4.0 Hz
1366 *
1367 * \returns Fault_BootIntoMotion Status Signal Value object
1368 */
1370
1371 /**
1372 * \brief Motion Detected during bootup.
1373 *
1374 * Default Value: False
1375 *
1376 * Default Rates:
1377 * CAN: 4.0 Hz
1378 *
1379 * \returns StickyFault_BootIntoMotion Status Signal Value object
1380 */
1382
1383 /**
1384 * \brief Motion stack data acquisition was slower than expected
1385 *
1386 * Default Value: False
1387 *
1388 * Default Rates:
1389 * CAN: 4.0 Hz
1390 *
1391 * \returns Fault_DataAcquiredLate Status Signal Value object
1392 */
1394
1395 /**
1396 * \brief Motion stack data acquisition was slower than expected
1397 *
1398 * Default Value: False
1399 *
1400 * Default Rates:
1401 * CAN: 4.0 Hz
1402 *
1403 * \returns StickyFault_DataAcquiredLate Status Signal Value object
1404 */
1406
1407 /**
1408 * \brief Motion stack loop time was slower than expected.
1409 *
1410 * Default Value: False
1411 *
1412 * Default Rates:
1413 * CAN: 4.0 Hz
1414 *
1415 * \returns Fault_LoopTimeSlow Status Signal Value object
1416 */
1418
1419 /**
1420 * \brief Motion stack loop time was slower than expected.
1421 *
1422 * Default Value: False
1423 *
1424 * Default Rates:
1425 * CAN: 4.0 Hz
1426 *
1427 * \returns StickyFault_LoopTimeSlow Status Signal Value object
1428 */
1430
1431 /**
1432 * \brief Magnetometer values are saturated
1433 *
1434 * Default Value: False
1435 *
1436 * Default Rates:
1437 * CAN: 4.0 Hz
1438 *
1439 * \returns Fault_SaturatedMagneter Status Signal Value object
1440 */
1442
1443 /**
1444 * \brief Magnetometer values are saturated
1445 *
1446 * Default Value: False
1447 *
1448 * Default Rates:
1449 * CAN: 4.0 Hz
1450 *
1451 * \returns StickyFault_SaturatedMagneter Status Signal Value object
1452 */
1454
1455 /**
1456 * \brief Accelerometer values are saturated
1457 *
1458 * Default Value: False
1459 *
1460 * Default Rates:
1461 * CAN: 4.0 Hz
1462 *
1463 * \returns Fault_SaturatedAccelometer Status Signal Value object
1464 */
1466
1467 /**
1468 * \brief Accelerometer values are saturated
1469 *
1470 * Default Value: False
1471 *
1472 * Default Rates:
1473 * CAN: 4.0 Hz
1474 *
1475 * \returns StickyFault_SaturatedAccelometer Status Signal Value object
1476 */
1478
1479 /**
1480 * \brief Gyroscope values are saturated
1481 *
1482 * Default Value: False
1483 *
1484 * Default Rates:
1485 * CAN: 4.0 Hz
1486 *
1487 * \returns Fault_SaturatedGyrosscope Status Signal Value object
1488 */
1490
1491 /**
1492 * \brief Gyroscope values are saturated
1493 *
1494 * Default Value: False
1495 *
1496 * Default Rates:
1497 * CAN: 4.0 Hz
1498 *
1499 * \returns StickyFault_SaturatedGyrosscope Status Signal Value object
1500 */
1502
1503
1504
1505 /**
1506 * \brief Control motor with generic control request object. User must make
1507 * sure the specified object is castable to a valid control request,
1508 * otherwise this function will fail at run-time and return the NotSupported
1509 * StatusCode
1510 *
1511 * \param request Control object to request of the device
1512 * \returns Status Code of the request, 0 is OK
1513 */
1514 ctre::phoenix::StatusCode SetControl(controls::ControlRequest& request)
1515 {
1516 controls::ControlRequest *ptr = &request;
1517 (void)ptr;
1518
1520 }
1521 /**
1522 * \brief Control motor with generic control request object. User must make
1523 * sure the specified object is castable to a valid control request,
1524 * otherwise this function will fail at run-time and return the corresponding
1525 * StatusCode
1526 *
1527 * \param request Control object to request of the device
1528 * \returns Status Code of the request, 0 is OK
1529 */
1530 ctre::phoenix::StatusCode SetControl(controls::ControlRequest&& request)
1531 {
1532 return SetControl(request);
1533 }
1534
1535
1536 /**
1537 * \brief The yaw to set the Pigeon2 to right now.
1538 *
1539 * \param newValue Value to set to.
1540 * \param timeoutSeconds Maximum time to wait up to in seconds.
1541 * \returns StatusCode of the set command
1542 */
1543 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
1544 {
1545 return GetConfigurator().SetYaw(newValue, timeoutSeconds);
1546 }
1547 /**
1548 * \brief The yaw to set the Pigeon2 to right now.
1549 *
1550 * This will wait up to 0.050 seconds (50ms) by default.
1551 *
1552 * \param newValue Value to set to.
1553 * \returns StatusCode of the set command
1554 */
1555 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
1556 {
1557 return SetYaw(newValue, 0.050_s);
1558 }
1559
1560 /**
1561 * \brief Clear the sticky faults in the device.
1562 *
1563 * \details This typically has no impact on the device functionality.
1564 * Instead, it just clears telemetry faults that are accessible via
1565 * API and Tuner Self-Test.
1566 * \param timeoutSeconds Maximum time to wait up to in seconds.
1567 * \returns StatusCode of the set command
1568 */
1569 ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
1570 {
1571 return GetConfigurator().ClearStickyFaults(timeoutSeconds);
1572 }
1573 /**
1574 * \brief Clear the sticky faults in the device.
1575 *
1576 * \details This typically has no impact on the device functionality.
1577 * Instead, it just clears telemetry faults that are accessible via
1578 * API and Tuner Self-Test.
1579 *
1580 * This will wait up to 0.050 seconds (50ms) by default.
1581 * \returns StatusCode of the set command
1582 */
1583 ctre::phoenix::StatusCode ClearStickyFaults()
1584 {
1585 return ClearStickyFaults(0.050_s);
1586 }
1587};
1588
1589}
1590}
1591
1592}
1593}
1594
ii that the Software will be uninterrupted or error free
Definition: CTRE_LICENSE.txt:191
CTREXPORT int c_ctre_phoenixpro_serialize_double(int spn, double value, char **str)
@ OK
No Error.
Definition: StatusCodes.h:1101
@ NotSupported
This is not supported.
Definition: StatusCodes.h:1704
Configs to trim the Pigeon2's gyroscope.
Definition: Configs.hpp:185
ctre::phoenix::StatusCode Deserialize(const std::string &string)
Definition: Configs.hpp:237
std::string ToString() const
Definition: Configs.hpp:215
std::string Serialize() const
Definition: Configs.hpp:227
Configs for Pigeon 2's Mount Pose configuration.
Definition: Configs.hpp:111
std::string Serialize() const
Definition: Configs.hpp:153
ctre::phoenix::StatusCode Deserialize(const std::string &string)
Definition: Configs.hpp:163
std::string ToString() const
Definition: Configs.hpp:141
Definition: Configurator.hpp:21
ctre::phoenix::StatusCode GetConfigsPrivate(std::string &serializedString, units::time::second_t timeoutSeconds) const
Definition: Configurator.hpp:61
units::time::second_t defaultTimeoutSeconds
The default amount of time to wait for a config.
Definition: Configurator.hpp:26
ctre::phoenix::StatusCode SetConfigsPrivate(const std::string &serializedString, units::time::second_t timeoutSeconds, bool futureProofConfigs, bool overrideIfDuplicate)
Definition: Configurator.hpp:37
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:40
std::string ToString() const
Get the string representation of this configuration.
Definition: CorePigeon2.hpp:89
bool FutureProofConfigs
True if we should factory default newer unsupported configs, false to leave newer unsupported configs...
Definition: CorePigeon2.hpp:55
GyroTrimConfigs GyroTrim
Configs to trim the Pigeon2's gyroscope.
Definition: CorePigeon2.hpp:76
Pigeon2FeaturesConfigs Pigeon2Features
Configs to enable/disable various features of the Pigeon2.
Definition: CorePigeon2.hpp:84
std::string Serialize() const
Get the serialized form of this configuration.
Definition: CorePigeon2.hpp:101
MountPoseConfigs MountPose
Configs for Pigeon 2's Mount Pose configuration.
Definition: CorePigeon2.hpp:65
ctre::phoenix::StatusCode Deserialize(const std::string &string)
Take a string and deserialize it to this configuration.
Definition: CorePigeon2.hpp:113
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:129
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:274
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:440
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:305
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:379
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:184
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:459
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:227
Pigeon2Configurator(const Pigeon2Configurator &)=delete
Delete the copy constructor, we can only pass by reference.
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:334
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:259
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:347
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:365
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:245
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:287
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:198
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:319
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:152
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:416
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:166
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:399
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:214
Configs to enable/disable various features of the Pigeon2.
Definition: Configs.hpp:256
std::string ToString() const
Definition: Configs.hpp:280
std::string Serialize() const
Definition: Configs.hpp:292
ctre::phoenix::StatusCode Deserialize(const std::string &string)
Definition: Configs.hpp:302
Abstract Control Request class that other control requests extend for use.
Definition: ControlRequest.hpp:65
Definition: DeviceIdentifier.hpp:19
Parent class for all devices.
Definition: ParentDevice.hpp:30
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:477
ctre::phoenix::StatusCode SetControl(controls::ControlRequest &request)
Control motor with generic control request object.
Definition: CorePigeon2.hpp:1514
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldY()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
configs::Pigeon2Configurator & GetConfigurator()
Gets the configurator for this Pigeon2.
Definition: CorePigeon2.hpp:526
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityY()
The angular velocity (ω) of the Pigeon 2 about the Y axis.
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldX()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
CorePigeon2(int deviceId, std::string canbus="")
Constructs a new Pigeon 2 sensor object.
StatusSignalValue< int > & GetVersionMajor()
App Major Version number.
StatusSignalValue< units::angle::degree_t > & GetAccumGyroY()
The accumulated gyro about the Y axis without any sensor fusing.
StatusSignalValue< bool > & GetTemperatureCompensationDisabled()
Whether the temperature-compensation feature is disabled.
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatW()
The W component of the reported Quaternion.
StatusSignalValue< bool > & GetStickyFault_SaturatedMagneter()
Magnetometer values are saturated.
StatusSignalValue< bool > & GetStickyFault_BootupAccelerometer()
Bootup checks failed: Accelerometer.
StatusSignalValue< bool > & GetStickyFault_BootIntoMotion()
Motion Detected during bootup.
StatusSignalValue< int > & GetVersionMinor()
App Minor Version number.
StatusSignalValue< units::time::second_t > & GetUpTime()
How long the Pigeon 2's been up in seconds, caps at 255 seconds.
StatusSignalValue< bool > & GetFault_SaturatedMagneter()
Magnetometer values are saturated.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:1555
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:1569
StatusSignalValue< bool > & GetStickyFault_SaturatedGyrosscope()
Gyroscope values are saturated.
StatusSignalValue< bool > & GetStickyFault_BootupMagnetometer()
Bootup checks failed: Magnetometer.
StatusSignalValue< bool > & GetNoMotionEnabled()
Whether the no-motion calibration feature is enabled.
ctre::phoenix::StatusCode SetControl(controls::ControlRequest &&request)
Control motor with generic control request object.
Definition: CorePigeon2.hpp:1530
StatusSignalValue< bool > & GetFault_Hardware()
Hardware fault occurred.
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldX()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignalValue< bool > & GetFault_BootupAccelerometer()
Bootup checks failed: Accelerometer.
StatusSignalValue< bool > & GetFault_BootDuringEnable()
Device boot while detecting the enable signal.
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityX()
The angular velocity (ω) of the Pigeon 2 about the X axis.
StatusSignalValue< units::acceleration::standard_gravity_t > & GetAccelerationZ()
The acceleration measured by Pigeon2 in the Z direction.
StatusSignalValue< units::acceleration::standard_gravity_t > & GetAccelerationY()
The acceleration measured by Pigeon2 in the Y direction.
StatusSignalValue< bool > & GetFault_BootIntoMotion()
Motion Detected during bootup.
StatusSignalValue< units::dimensionless::scalar_t > & GetGravityVectorX()
The X component of the gravity vector.
StatusSignalValue< units::acceleration::standard_gravity_t > & GetAccelerationX()
The acceleration measured by Pigeon2 in the X direction.
StatusSignalValue< units::angle::degree_t > & GetAccumGyroZ()
The accumulated gyro about the Z axis without any sensor fusing.
StatusSignalValue< units::dimensionless::scalar_t > & GetNoMotionCount()
The number of times a no-motion event occurred, wraps at 15.
StatusSignalValue< units::temperature::celsius_t > & GetTemperature()
Temperature of the Pigeon 2.
StatusSignalValue< bool > & GetFault_BootupGyroscope()
Bootup checks failed: Gyroscope.
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatX()
The X component of the reported Quaternion.
StatusSignalValue< int > & GetVersionBuild()
App Build Version number.
StatusSignalValue< bool > & GetStickyFault_BootDuringEnable()
Device boot while detecting the enable signal.
StatusSignalValue< units::angle::degree_t > & GetPitch()
Current reported pitch of the Pigeon2.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:1583
StatusSignalValue< bool > & GetFault_SaturatedAccelometer()
Accelerometer values are saturated.
CorePigeon2(CorePigeon2 const &)=delete
StatusSignalValue< bool > & GetStickyFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected.
StatusSignalValue< int > & GetVersionBugfix()
App Bugfix Version number.
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatY()
The Y component of the reported Quaternion.
StatusSignalValue< bool > & GetFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected.
StatusSignalValue< bool > & GetFault_SaturatedGyrosscope()
Gyroscope values are saturated.
StatusSignalValue< bool > & GetStickyFault_Undervoltage()
Device supply voltage dropped to near brownout levels.
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZ()
The angular velocity (ω) of the Pigeon 2 about the Z axis.
StatusSignalValue< bool > & GetStickyFault_LoopTimeSlow()
Motion stack loop time was slower than expected.
StatusSignalValue< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
configs::Pigeon2Configurator const & GetConfigurator() const
Gets the configurator for this Pigeon2.
Definition: CorePigeon2.hpp:538
StatusSignalValue< bool > & GetFault_LoopTimeSlow()
Motion stack loop time was slower than expected.
StatusSignalValue< units::angle::degree_t > & GetAccumGyroX()
The accumulated gyro about the X axis without any sensor fusing.
StatusSignalValue< units::voltage::volt_t > & GetSupplyVoltage()
Measured supply voltage to the Pigeon2.
StatusSignalValue< units::dimensionless::scalar_t > & GetGravityVectorZ()
The Z component of the gravity vector.
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldY()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldZ()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
StatusSignalValue< units::angle::degree_t > & GetRoll()
Current reported roll of the Pigeon2.
StatusSignalValue< bool > & GetStickyFault_SaturatedAccelometer()
Accelerometer values are saturated.
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatZ()
The Z component of the reported Quaternion.
StatusSignalValue< int > & GetStickyFaultField()
Integer representing all sticky faults.
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:1543
StatusSignalValue< units::dimensionless::scalar_t > & GetGravityVectorY()
The Y component of the gravity vector.
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldZ()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
StatusSignalValue< bool > & GetStickyFault_BootupGyroscope()
Bootup checks failed: Gyroscope.
StatusSignalValue< int > & GetVersion()
Full Version.
CorePigeon2 & operator=(CorePigeon2 const &)=delete
sim::Pigeon2SimState & GetSimState()
Get the simulation state for this device.
Definition: CorePigeon2.hpp:556
StatusSignalValue< bool > & GetFault_BootupMagnetometer()
Bootup checks failed: Magnetometer.
StatusSignalValue< int > & GetFaultField()
Integer representing all faults.
StatusSignalValue< bool > & GetStickyFault_Hardware()
Hardware fault occurred.
StatusSignalValue< bool > & GetFault_Undervoltage()
Device supply voltage dropped to near brownout levels.
Class to control the state of a simulated hardware::Pigeon2.
Definition: Pigeon2SimState.hpp:30
static constexpr int Startup_ResetFlags
Definition: SpnValue.hpp:26
CTREXPORT double GetCurrentTimeSeconds()
Get the current timestamp in seconds.
Definition: string_util.hpp:14