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