CTRE Phoenix C++ 5.33.1
PigeonIMU.h
Go to the documentation of this file.
1/* Copyright (C) Cross The Road Electronics 2024 */
2/*
3 * Software License Agreement
4 *
5 * Copyright (C) Cross The Road Electronics. All rights
6 * reserved.
7 *
8 * Cross The Road Electronics (CTRE) licenses to you the right to
9 * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software
10 * API Libraries ONLY when in use with Cross The Road Electronics hardware products.
11 *
12 * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
13 * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT
14 * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A
15 * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL
16 * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL,
17 * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF
18 * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS
19 * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE
20 * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER
21 * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT
22 * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE
23 */
24
25#pragma once
26
27#include <string>
29
30/* forward prototype */
31namespace ctre {
32namespace phoenix {
33namespace motorcontrol {
34namespace can {
35class TalonSRX;
36}
37}
38}
39}
40
41namespace ctre {
42namespace phoenix {
43/** sensors namespace */
44namespace sensors {
45
46/**
47 * Configurables available to Pigeon
48 */
51
52 /**
53 * @return String representation of configs
54 */
55 std::string toString() {
56 return toString("");
57 }
58
59 /**
60 * @param prependString
61 * String to prepend to configs
62 * @return String representation of configs
63 */
64 std::string toString(std::string prependString) {
65 std::string retstr = BasePigeonConfiguration::toString(prependString);
66
67 return retstr;
68 }
69};// struct PigeonIMU
70
71/**
72 * Util class to help with Pigeon configurations
73 */
75private:
76 static PigeonIMUConfiguration _default;
77public:
78 /** @} */
79};
80
81/**
82 * Pigeon IMU Class.
83 * Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).
84 */
85class PigeonIMU: public BasePigeon {
86public:
87 /** Data object for holding fusion information. */
88 struct FusionStatus {
89 /**
90 * Fused Heading
91 */
92 double heading;
93 /**
94 * Whether the fusion is valid
95 */
97 /**
98 * Whether the pigeon is fusing
99 */
101 /**
102 * Description of fusion status
103 */
104 std::string description;
105 /**
106 * Same as GetLastError()
107 */
109 };
110 /**
111 * Various calibration modes supported by Pigeon.
112 *
113 * Note that you can instead use Phoenix Tuner to accomplish certain calibrations.
114 *
115 */
117 /**
118 * Boot-Calibrate the pigeon
119 */
121 /**
122 * Temperature-Calibrate the pigeon
123 */
125 /**
126 * Magnetometer-Calibrate the pigeon using the 12pt process
127 */
129 /**
130 * Magnetometer-Calibrate the pigeon using 360 turns
131 */
133 /**
134 * Calibrate the pigeon accelerometer
135 */
137 };
138 /** Overall state of the Pigeon. */
140 /**
141 * No communications with Pigeon
142 */
144 /**
145 * Pigeon is initializing
146 */
148 /**
149 * Pigeon is ready
150 */
152 /**
153 * Pigeon is calibrating due to user
154 */
156 };
157 /**
158 * Data object for status on current calibration and general status.
159 *
160 * Pigeon has many calibration modes supported for a variety of uses.
161 * The modes generally collects and saves persistently information that makes
162 * the Pigeon signals more accurate. This includes collecting temperature, gyro, accelerometer,
163 * and compass information.
164 *
165 * For FRC use-cases, typically compass and temperature calibration is not required.
166 *
167 * Additionally when motion driver software in the Pigeon boots, it will perform a fast boot calibration
168 * to initially bias gyro and setup accelerometer.
169 *
170 * These modes can be enabled with the EnterCalibration mode.
171 *
172 * When a calibration mode is entered, caller can expect...
173 *
174 * - PigeonState to reset to Initializing and bCalIsBooting is set to true. Pigeon LEDs will blink the boot pattern.
175 * This is similar to the normal boot cal, however it can an additional ~30 seconds since calibration generally
176 * requires more information.
177 * currentMode will reflect the user's selected calibration mode.
178 *
179 * - PigeonState will eventually settle to UserCalibration and Pigeon LEDs will show cal specific blink patterns.
180 * bCalIsBooting is now false.
181 *
182 * - Follow the instructions in the Pigeon User Manual to meet the calibration specific requirements.
183 * When finished calibrationError will update with the result.
184 * Pigeon will solid-fill LEDs with red (for failure) or green (for success) for ~5 seconds.
185 * Pigeon then perform boot-cal to cleanly apply the newly saved calibration data.
186 */
188 /**
189 * The current state of the motion driver. This reflects if the sensor signals are accurate.
190 * Most calibration modes will force Pigeon to reinit the motion driver.
191 */
193 /**
194 * The currently applied calibration mode if state is in UserCalibration or if bCalIsBooting is true.
195 * Otherwise it holds the last selected calibration mode (when calibrationError was updated).
196 */
198 /**
199 * The error code for the last calibration mode.
200 * Zero represents a successful cal (with solid green LEDs at end of cal)
201 * and nonzero is a failed calibration (with solid red LEDs at end of cal).
202 * Different calibration
203 */
205 /**
206 * After caller requests a calibration mode, pigeon will perform a boot-cal before
207 * entering the requested mode. During this period, this flag is set to true.
208 */
210 /**
211 * general string description of current status
212 */
213 std::string description;
214 /**
215 * Temperature in Celsius
216 */
217 double tempC;
218 /**
219 * Number of seconds Pigeon has been up (since boot).
220 * This register is reset on power boot or processor reset.
221 * Register is capped at 255 seconds with no wrap around.
222 */
224 /**
225 * Number of times the Pigeon has automatically rebiased the gyro.
226 * This counter overflows from 15 -> 0 with no cap.
227 */
229 /**
230 * Number of times the Pigeon has temperature compensated the various signals.
231 * This counter overflows from 15 -> 0 with no cap.
232 */
234 /**
235 * Same as GetLastError()
236 */
238 };
239
240 /**
241 * Create a Pigeon object that communicates with Pigeon on CAN Bus.
242 *
243 * @param deviceNumber
244 * CAN Device Id of Pigeon [0,62]
245 */
246 PigeonIMU(int deviceNumber);
247 /**
248 * Create a Pigeon object that communciates with Pigeon through the
249 * Gadgeteer ribbon cable connected to a Talon on CAN Bus.
250 *
251 * [[deprecated("Pass in a TalonSRX reference instead.")]]
252 *
253 * @param talonSrx
254 * Object for the TalonSRX connected via ribbon cable.
255 */
257 /**
258 * Create a Pigeon object that communciates with Pigeon through the
259 * Gadgeteer ribbon cable connected to a Talon on CAN Bus.
260 *
261 * @param talonSrx
262 * Object for the TalonSRX connected via ribbon cable.
263 */
265
266 /**
267 * Sets the Fused Heading to the specified value.
268 *
269 * @param angleDeg New fused-heading in degrees [+/- 23,040 degrees]
270 * @param timeoutMs
271 * Timeout value in ms. If nonzero, function will wait for
272 * config success and report an error if it times out.
273 * If zero, no blocking or checking is performed.
274 * @return Error Code generated by function. 0 indicates no error.
275 */
276 int SetFusedHeading(double angleDeg, int timeoutMs = 0);
277 /**
278 * Atomically add to the Fused Heading register.
279 *
280 * @param angleDeg Degrees to add to the Fused Heading register.
281 * @param timeoutMs
282 * Timeout value in ms. If nonzero, function will wait for
283 * config success and report an error if it times out.
284 * If zero, no blocking or checking is performed.
285 * @return Error Code generated by function. 0 indicates no error.
286 */
287 int AddFusedHeading(double angleDeg, int timeoutMs = 0);
288 /**
289 * Sets the Fused Heading register to match the current compass value.
290 *
291 * @param timeoutMs
292 * Timeout value in ms. If nonzero, function will wait for
293 * config success and report an error if it times out.
294 * If zero, no blocking or checking is performed.
295 * @return Error Code generated by function. 0 indicates no error.
296 */
297 int SetFusedHeadingToCompass(int timeoutMs = 0);
298
299 /**
300 * Disable/Enable Temp compensation. Pigeon has this on/False at boot.
301 *
302 * @param bTempCompDisable Set to "False" to enable temperature compensation.
303 * @param timeoutMs
304 * Timeout value in ms. If nonzero, function will wait for
305 * config success and report an error if it times out.
306 * If zero, no blocking or checking is performed.
307 * @return Error Code generated by function. 0 indicates no error.
308 */
309 int SetTemperatureCompensationDisable(bool bTempCompDisable,
310 int timeoutMs = 0);
311 /**
312 * Set the declination for compass. Declination is the difference between
313 * Earth Magnetic north, and the geographic "True North".
314 *
315 * @param angleDegOffset Degrees to set Compass Declination to.
316 * @param timeoutMs
317 * Timeout value in ms. If nonzero, function will wait for
318 * config success and report an error if it times out.
319 * If zero, no blocking or checking is performed.
320 * @return Error Code generated by function. 0 indicates no error.
321 */
322 int SetCompassDeclination(double angleDegOffset, int timeoutMs = 0);
323 /**
324 * Sets the compass angle. Although compass is absolute [0,360) degrees, the
325 * continuous compass register holds the wrap-arounds.
326 *
327 * @param angleDeg Degrees to set continuous compass angle to.
328 * @param timeoutMs
329 * Timeout value in ms. If nonzero, function will wait for
330 * config success and report an error if it times out.
331 * If zero, no blocking or checking is performed.
332 * @return Error Code generated by function. 0 indicates no error.
333 */
334 int SetCompassAngle(double angleDeg, int timeoutMs = 0);
335
336 /**
337 * Enters the Calbration mode. See the Pigeon IMU documentation for More
338 * information on Calibration.
339 *
340 * Note that you can instead use Phoenix Tuner to accomplish this.
341 * Note you should NOT be calling this during normal robot operation.
342 *
343 * @param calMode Calibration to execute
344 * @param timeoutMs
345 * Timeout value in ms. If nonzero, function will wait for
346 * config success and report an error if it times out.
347 * If zero, no blocking or checking is performed.
348 * @return Error Code generated by function. 0 indicates no error.
349 */
350 int EnterCalibrationMode(CalibrationMode calMode, int timeoutMs = 0);
351 /**
352 * Get the status of the current (or previousley complete) calibration.
353 *
354 * @param [out] statusToFill Container for the status information.
355 * @return Error Code generated by function. 0 indicates no error.
356 */
358 /**
359 * Gets the current Pigeon state
360 *
361 * @return PigeonState enum
362 */
364 /**
365 * Get Accelerometer tilt angles.
366 *
367 * @param tiltAngles Array to fill with x[0], y[1], and z[2] angles in degrees.
368 * @return The last ErrorCode generated.
369 */
370 int GetAccelerometerAngles(double tiltAngles[3]);
371 /**
372 * Get the current Fusion Status (including fused heading)
373 *
374 * @param status object reference to fill with fusion status flags.
375 * Caller may pass null if flags are not needed.
376 * @return The fused heading in degrees.
377 */
379 /**
380 * Gets the Fused Heading
381 *
382 * @return The fused heading in degrees.
383 */
384 double GetFusedHeading() const;
385 /**
386 * @return number of times Pigeon Reset
387 */
388 uint32_t GetResetCount();
389 /**
390 * @return Reset flags for Pigeon
391 */
392 uint32_t GetResetFlags();
393
394 /**
395 * Gets the string representation of a PigeonState
396 * @param state PigeonState to get the string representation of
397 * @return string representation of specified PigeonState
398 */
399 static std::string ToString(PigeonIMU::PigeonState state);
400 /**
401 * Gets the string representation of a CalibrationMode
402 * @param cm CalibrationMode to get the string representation of
403 * @return string representation of specified CalibrationMode
404 */
405 static std::string ToString(CalibrationMode cm);
406
407 /**
408 * Sets the value of a custom parameter. This is for arbitrary use.
409 *
410 * Sometimes it is necessary to save calibration/declination/offset
411 * information in the device. Particularly if the
412 * device is part of a subsystem that can be replaced.
413 *
414 * @param newValue
415 * Value for custom parameter.
416 * @param paramIndex
417 * Index of custom parameter. [0-1]
418 * @param timeoutMs
419 * Timeout value in ms. If nonzero, function will wait for
420 * config success and report an error if it times out.
421 * If zero, no blocking or checking is performed.
422 * @return Error Code generated by function. 0 indicates no error.
423 */
424 ErrorCode ConfigSetCustomParam(int newValue, int paramIndex, int timeoutMs = 0);
425 /**
426 * Gets the value of a custom parameter. This is for arbitrary use.
427 *
428 * Sometimes it is necessary to save calibration/declination/offset
429 * information in the device. Particularly if the
430 * device is part of a subsystem that can be replaced.
431 *
432 * @param paramIndex
433 * Index of custom parameter. [0-1]
434 * @param timeoutMs
435 * Timeout value in ms. If nonzero, function will wait for
436 * config success and report an error if it times out.
437 * If zero, no blocking or checking is performed.
438 * @return Value of the custom param.
439 */
440 int ConfigGetCustomParam(int paramIndex, int timeoutMs = 0);
441
442 /**
443 * Sets the period of the given status frame.
444 *
445 * @param statusFrame
446 * Frame whose period is to be changed.
447 * @param periodMs
448 * Period in ms for the given frame.
449 * @param timeoutMs
450 * Timeout value in ms. If nonzero, function will wait for
451 * config success and report an error if it times out.
452 * If zero, no blocking or checking is performed.
453 * @return Error Code generated by function. 0 indicates no error.
454 */
456 int timeoutMs = 0);
457
458 /**
459 * Gets the period of the given status frame.
460 *
461 * @param frame
462 * Frame to get the period of.
463 * @param timeoutMs
464 * Timeout value in ms. If nonzero, function will wait for
465 * config success and report an error if it times out.
466 * If zero, no blocking or checking is performed.
467 * @return Period of the given status frame.
468 */
470 int timeoutMs = 0) ;
471 /**
472 * Sets the period of the given control frame.
473 *
474 * @param frame
475 * Frame whose period is to be changed.
476 * @param periodMs
477 * Period in ms for the given frame.
478 * @return Error Code generated by function. 0 indicates no error.
479 */
481 int periodMs);
482 /**
483 * Gets the firmware version of the device.
484 *
485 * @return param holds the firmware version of the device. Device must be powered
486 * cycled at least once.
487 */
489 /**
490 * Gets the fault status
491 *
492 * @param toFill
493 * Container for fault statuses.
494 * @return Error Code generated by function. 0 indicates no error.
495 */
497 /**
498 * Gets the sticky fault status
499 *
500 * @param toFill
501 * Container for sticky fault statuses.
502 * @return Error Code generated by function. 0 indicates no error.
503 */
505 /**
506 * Clears the Sticky Faults
507 *
508 * @return Error Code generated by function. 0 indicates no error.
509 */
510 ErrorCode ClearStickyFaults(int timeoutMs = 0);
511
512 //------ All Configs ----------//
513 /**
514 * Configures all persistent settings.
515 *
516 * @param allConfigs Object with all of the persistant settings
517 * @param timeoutMs
518 * Timeout value in ms. If nonzero, function will wait for
519 * config success and report an error if it times out.
520 * If zero, no blocking or checking is performed.
521 *
522 * @return Error Code generated by function. 0 indicates no error.
523 */
524 virtual ctre::phoenix::ErrorCode ConfigAllSettings(const PigeonIMUConfiguration &allConfigs, int timeoutMs = 50);
525 /**
526 * Gets all persistant settings.
527 *
528 * @param allConfigs Object with all of the persistant settings
529 * @param timeoutMs
530 * Timeout value in ms. If nonzero, function will wait for
531 * config success and report an error if it times out.
532 * If zero, no blocking or checking is performed.
533 */
534 virtual void GetAllConfigs(PigeonIMUConfiguration &allConfigs, int timeoutMs = 50);
535 /**
536 * Configures all persistent settings to defaults.
537 *
538 * @param timeoutMs
539 * Timeout value in ms. If nonzero, function will wait for
540 * config success and report an error if it times out.
541 * If zero, no blocking or checking is performed.
542 *
543 * @return Error Code generated by function. 0 indicates no error.
544 */
545 virtual ErrorCode ConfigFactoryDefault(int timeoutMs = 50);
546private:
547 /** firmware state reported over CAN */
548 enum MotionDriverState {
549 Init0 = 0,
550 WaitForPowerOff = 1,
551 ConfigAg = 2,
552 SelfTestAg = 3,
553 StartDMP = 4,
554 ConfigCompass_0 = 5,
555 ConfigCompass_1 = 6,
556 ConfigCompass_2 = 7,
557 ConfigCompass_3 = 8,
558 ConfigCompass_4 = 9,
559 ConfigCompass_5 = 10,
560 SelfTestCompass = 11,
561 WaitForGyroStable = 12,
562 AdditionalAccelAdjust = 13,
563 Idle = 14,
564 Calibration = 15,
565 LedInstrum = 16,
566 Error = 31,
567 };
568 /** sub command for the various Set param enums */
569 enum TareType {
570 SetValue = 0x00, AddOffset = 0x01, MatchCompass = 0x02, SetOffset = 0xFF,
571 };
572 /** data storage for reset signals */
573 struct ResetStats {
574 int32_t resetCount;
575 int32_t resetFlags;
576 int32_t firmVers;
577 bool hasReset;
578 };
579 ResetStats _resetStats = { 0, 0, 0, false };
580
581 /** Portion of the arbID for all status and control frames. */
582 uint32_t _usageHist = 0;
583 uint64_t _cache;
584 uint32_t _len;
585
586 /** overall threshold for when frame data is too old */
587 const uint32_t EXPECTED_RESPONSE_TIMEOUT_MS = (200);
588
589 int PrivateSetParameter(ParamEnum paramEnum, TareType tareType,
590 double angleDeg, int timeoutMs = 0);
591
592 PigeonIMU::PigeonState GetState(int errCode, const uint64_t & statusFrame);
593 double GetTemp(const uint64_t & statusFrame);
594
595
596
597
598};// class PigeonIMU
599} // namespace signals
600} // namespace phoenix
601} // namespace ctre
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: TalonSRX.h:145
Pigeon IMU Class.
Definition: BasePigeon.h:101
double GetTemp() const
Gets the temperature of the pigeon.
Pigeon IMU Class.
Definition: PigeonIMU.h:85
virtual ErrorCode ConfigFactoryDefault(int timeoutMs=50)
Configures all persistent settings to defaults.
int EnterCalibrationMode(CalibrationMode calMode, int timeoutMs=0)
Enters the Calbration mode.
ErrorCode GetFaults(PigeonIMU_Faults &toFill)
Gets the fault status.
int SetFusedHeading(double angleDeg, int timeoutMs=0)
Sets the Fused Heading to the specified value.
ErrorCode ClearStickyFaults(int timeoutMs=0)
Clears the Sticky Faults.
int SetCompassAngle(double angleDeg, int timeoutMs=0)
Sets the compass angle.
int SetFusedHeadingToCompass(int timeoutMs=0)
Sets the Fused Heading register to match the current compass value.
PigeonIMU(int deviceNumber)
Create a Pigeon object that communicates with Pigeon on CAN Bus.
ErrorCode SetControlFramePeriod(PigeonIMU_ControlFrame frame, int periodMs)
Sets the period of the given control frame.
ErrorCode GetStickyFaults(PigeonIMU_StickyFaults &toFill)
Gets the sticky fault status.
double GetFusedHeading() const
Gets the Fused Heading.
int GetAccelerometerAngles(double tiltAngles[3])
Get Accelerometer tilt angles.
PigeonIMU(ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx)
Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon cable connected to ...
int SetCompassDeclination(double angleDegOffset, int timeoutMs=0)
Set the declination for compass.
static std::string ToString(CalibrationMode cm)
Gets the string representation of a CalibrationMode.
ErrorCode SetStatusFramePeriod(PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0)
Sets the period of the given status frame.
int ConfigGetCustomParam(int paramIndex, int timeoutMs=0)
Gets the value of a custom parameter.
double GetFusedHeading(FusionStatus &status)
Get the current Fusion Status (including fused heading)
CalibrationMode
Various calibration modes supported by Pigeon.
Definition: PigeonIMU.h:116
@ BootTareGyroAccel
Boot-Calibrate the pigeon.
Definition: PigeonIMU.h:120
@ Magnetometer360
Magnetometer-Calibrate the pigeon using 360 turns.
Definition: PigeonIMU.h:132
@ Magnetometer12Pt
Magnetometer-Calibrate the pigeon using the 12pt process.
Definition: PigeonIMU.h:128
@ Accelerometer
Calibrate the pigeon accelerometer.
Definition: PigeonIMU.h:136
@ Temperature
Temperature-Calibrate the pigeon.
Definition: PigeonIMU.h:124
PigeonState
Overall state of the Pigeon.
Definition: PigeonIMU.h:139
@ NoComm
No communications with Pigeon.
Definition: PigeonIMU.h:143
@ Initializing
Pigeon is initializing.
Definition: PigeonIMU.h:147
@ UserCalibration
Pigeon is calibrating due to user.
Definition: PigeonIMU.h:155
@ Ready
Pigeon is ready.
Definition: PigeonIMU.h:151
int SetTemperatureCompensationDisable(bool bTempCompDisable, int timeoutMs=0)
Disable/Enable Temp compensation.
int GetGeneralStatus(PigeonIMU::GeneralStatus &statusToFill)
Get the status of the current (or previousley complete) calibration.
ErrorCode ConfigSetCustomParam(int newValue, int paramIndex, int timeoutMs=0)
Sets the value of a custom parameter.
int GetStatusFramePeriod(PigeonIMU_StatusFrame frame, int timeoutMs=0)
Gets the period of the given status frame.
virtual ctre::phoenix::ErrorCode ConfigAllSettings(const PigeonIMUConfiguration &allConfigs, int timeoutMs=50)
Configures all persistent settings.
virtual void GetAllConfigs(PigeonIMUConfiguration &allConfigs, int timeoutMs=50)
Gets all persistant settings.
int GetFirmwareVersion()
Gets the firmware version of the device.
PigeonState GetState()
Gets the current Pigeon state.
PigeonIMU(ctre::phoenix::motorcontrol::can::TalonSRX *talonSrx)
Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon cable connected to ...
int AddFusedHeading(double angleDeg, int timeoutMs=0)
Atomically add to the Fused Heading register.
static std::string ToString(PigeonIMU::PigeonState state)
Gets the string representation of a PigeonState.
PigeonIMU_StatusFrame
Enumerated type for status frame types.
Definition: PigeonIMU_StatusFrame.h:9
PigeonIMU_ControlFrame
Enumerated type for status frame types.
Definition: PigeonIMU_ControlFrame.h:9
ParamEnum
Signal enumeration for generic signal access.
Definition: paramEnum.h:13
ErrorCode
Definition: ErrorCode.h:13
namespace ctre
Definition: paramEnum.h:5
Util class to help with Pigeon configurations.
Definition: BasePigeon.h:82
Configurables available to Pigeon.
Definition: BasePigeon.h:57
std::string toString()
Definition: BasePigeon.h:63
Data object for holding fusion information.
Definition: PigeonIMU.h:88
bool bIsValid
Whether the fusion is valid.
Definition: PigeonIMU.h:96
bool bIsFusing
Whether the pigeon is fusing.
Definition: PigeonIMU.h:100
int lastError
Same as GetLastError()
Definition: PigeonIMU.h:108
double heading
Fused Heading.
Definition: PigeonIMU.h:92
std::string description
Description of fusion status.
Definition: PigeonIMU.h:104
Data object for status on current calibration and general status.
Definition: PigeonIMU.h:187
bool bCalIsBooting
After caller requests a calibration mode, pigeon will perform a boot-cal before entering the requeste...
Definition: PigeonIMU.h:209
int noMotionBiasCount
Number of times the Pigeon has automatically rebiased the gyro.
Definition: PigeonIMU.h:228
int tempCompensationCount
Number of times the Pigeon has temperature compensated the various signals.
Definition: PigeonIMU.h:233
std::string description
general string description of current status
Definition: PigeonIMU.h:213
int lastError
Same as GetLastError()
Definition: PigeonIMU.h:237
PigeonIMU::CalibrationMode currentMode
The currently applied calibration mode if state is in UserCalibration or if bCalIsBooting is true.
Definition: PigeonIMU.h:197
int calibrationError
The error code for the last calibration mode.
Definition: PigeonIMU.h:204
PigeonIMU::PigeonState state
The current state of the motion driver.
Definition: PigeonIMU.h:192
double tempC
Temperature in Celsius.
Definition: PigeonIMU.h:217
int upTimeSec
Number of seconds Pigeon has been up (since boot).
Definition: PigeonIMU.h:223
Sticky faults available to Pigeon.
Definition: PigeonIMU_Faults.h:13
Sticky faults available to Pigeon.
Definition: PigeonIMU_StickyFaults.h:13
Util class to help with Pigeon configurations.
Definition: PigeonIMU.h:74
Configurables available to Pigeon.
Definition: PigeonIMU.h:49
PigeonIMUConfiguration()
Definition: PigeonIMU.h:50
std::string toString(std::string prependString)
Definition: PigeonIMU.h:64
std::string toString()
Definition: PigeonIMU.h:55