WPILibC++ 2024.3.2
ADIS16448_IMU.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5/*----------------------------------------------------------------------------*/
6/* Copyright (c) 2016-2020 Analog Devices Inc. All Rights Reserved. */
7/* Open Source Software - may be modified and shared by FRC teams. The code */
8/* must be accompanied by the FIRST BSD license file in the root directory of */
9/* the project. */
10/* */
11/* Modified by Juan Chong - frcsupport@analog.com */
12/*----------------------------------------------------------------------------*/
13
14#pragma once
15
16#include <stdint.h>
17
18#include <atomic>
19#include <thread>
20
21#include <hal/SimDevice.h>
22#include <units/acceleration.h>
23#include <units/angle.h>
26#include <units/pressure.h>
27#include <units/temperature.h>
29#include <wpi/mutex.h>
32
33#include "frc/DigitalInput.h"
34#include "frc/DigitalOutput.h"
35#include "frc/SPI.h"
36
37namespace frc {
38/**
39 * Use DMA SPI to read rate, acceleration, and magnetometer data from the
40 * ADIS16448 IMU and return the robots heading relative to a starting position,
41 * AHRS, and instant measurements
42 *
43 * The ADIS16448 gyro angle outputs track the robot's heading based on the
44 * starting position. As the robot rotates the new heading is computed by
45 * integrating the rate of rotation returned by the IMU. When the class is
46 * instantiated, a short calibration routine is performed where the IMU samples
47 * the gyros while at rest to determine the initial offset. This is subtracted
48 * from each sample to determine the heading.
49 *
50 * This class is for the ADIS16448 IMU connected via the SPI port available on
51 * the RoboRIO MXP port.
52 */
53
55 public wpi::SendableHelper<ADIS16448_IMU> {
56 public:
57 /**
58 * ADIS16448 calibration times.
59 */
60 enum class CalibrationTime {
61 /// 32 ms calibration time.
62 _32ms = 0,
63 /// 64 ms calibration time.
64 _64ms = 1,
65 /// 128 ms calibration time.
66 _128ms = 2,
67 /// 256 ms calibration time.
68 _256ms = 3,
69 /// 512 ms calibration time.
70 _512ms = 4,
71 /// 1 s calibration time.
72 _1s = 5,
73 /// 2 s calibration time.
74 _2s = 6,
75 /// 4 s calibration time.
76 _4s = 7,
77 /// 8 s calibration time.
78 _8s = 8,
79 /// 16 s calibration time.
80 _16s = 9,
81 /// 32 s calibration time.
82 _32s = 10,
83 /// 64 s calibration time.
84 _64s = 11
85 };
86
87 /**
88 * IMU axes.
89 */
90 enum IMUAxis {
91 /// The IMU's X axis.
93 /// The IMU's Y axis.
95 /// The IMU's Z axis.
96 kZ
97 };
98
99 /**
100 * IMU constructor on onboard MXP CS0, Z-up orientation, and complementary
101 * AHRS computation.
102 */
104
105 /**
106 * IMU constructor on the specified MXP port and orientation.
107 *
108 * @param yaw_axis The axis where gravity is present. Valid options are kX,
109 * kY, and kZ
110 * @param port The SPI port where the IMU is connected.
111 * @param cal_time The calibration time that should be used on start-up.
112 */
113 explicit ADIS16448_IMU(IMUAxis yaw_axis, SPI::Port port,
114 CalibrationTime cal_time);
115
116 ~ADIS16448_IMU() override;
117
120
121 /**
122 * Initialize the IMU.
123 *
124 * Perform gyro offset calibration by collecting data for a number of seconds
125 * and computing the center value. The center value is subtracted from
126 * subsequent measurements.
127 *
128 * It's important to make sure that the robot is not moving while the
129 * centering calculations are in progress, this is typically done when the
130 * robot is first turned on while it's sitting at rest before the match
131 * starts.
132 *
133 * The calibration routine can be triggered by the user during runtime.
134 */
135 void Calibrate();
136
137 /**
138 * Configures the calibration time used for the next calibrate.
139 *
140 * @param new_cal_time The calibration time that should be used
141 */
143
144 /**
145 * Reset the gyro.
146 *
147 * Resets the gyro accumulations to a heading of zero. This can be used if
148 * there is significant drift in the gyro and it needs to be recalibrated
149 * after running.
150 */
151 void Reset();
152
153 /**
154 * Returns the yaw axis angle in degrees (CCW positive).
155 */
156 units::degree_t GetAngle() const;
157
158 /**
159 * Returns the yaw axis angular rate in degrees per second (CCW positive).
160 */
161 units::degrees_per_second_t GetRate() const;
162
163 /**
164 * Returns the accumulated gyro angle in the X axis.
165 */
166 units::degree_t GetGyroAngleX() const;
167
168 /**
169 * Returns the accumulated gyro angle in the Y axis.
170 */
171 units::degree_t GetGyroAngleY() const;
172
173 /**
174 * Returns the accumulated gyro angle in the Z axis.
175 */
176 units::degree_t GetGyroAngleZ() const;
177
178 /**
179 * Returns the angular rate in the X axis.
180 */
181 units::degrees_per_second_t GetGyroRateX() const;
182
183 /**
184 * Returns the angular rate in the Y axis.
185 */
186 units::degrees_per_second_t GetGyroRateY() const;
187
188 /**
189 * Returns the angular rate in the Z axis.
190 */
191 units::degrees_per_second_t GetGyroRateZ() const;
192
193 /**
194 * Returns the acceleration in the X axis.
195 */
196 units::meters_per_second_squared_t GetAccelX() const;
197
198 /**
199 * Returns the acceleration in the Y axis.
200 */
201 units::meters_per_second_squared_t GetAccelY() const;
202
203 /**
204 * Returns the acceleration in the Z axis.
205 */
206 units::meters_per_second_squared_t GetAccelZ() const;
207
208 /**
209 * Returns the complementary angle around the X axis computed from
210 * accelerometer and gyro rate measurements.
211 */
212 units::degree_t GetXComplementaryAngle() const;
213
214 /**
215 * Returns the complementary angle around the Y axis computed from
216 * accelerometer and gyro rate measurements.
217 */
218 units::degree_t GetYComplementaryAngle() const;
219
220 /**
221 * Returns the X-axis filtered acceleration angle.
222 */
223 units::degree_t GetXFilteredAccelAngle() const;
224
225 /**
226 * Returns the Y-axis filtered acceleration angle.
227 */
228 units::degree_t GetYFilteredAccelAngle() const;
229
230 /**
231 * Returns the magnetic field strength in the X axis.
232 */
233 units::tesla_t GetMagneticFieldX() const;
234
235 /**
236 * Returns the magnetic field strength in the Y axis.
237 */
238 units::tesla_t GetMagneticFieldY() const;
239
240 /**
241 * Returns the magnetic field strength in the Z axis.
242 */
243 units::tesla_t GetMagneticFieldZ() const;
244
245 /**
246 * Returns the barometric pressure.
247 */
248 units::pounds_per_square_inch_t GetBarometricPressure() const;
249
250 /**
251 * Returns the temperature.
252 */
253 units::celsius_t GetTemperature() const;
254
256
257 int SetYawAxis(IMUAxis yaw_axis);
258
259 /**
260 * Checks the connection status of the IMU.
261 *
262 * @return True if the IMU is connected, false otherwise.
263 */
264 bool IsConnected() const;
265
266 /**
267 * Configures the decimation rate of the IMU.
268 *
269 * @param decimationRate The new decimation value.
270 * @return 0 if success, 1 if no change, 2 if error.
271 */
272 int ConfigDecRate(uint16_t decimationRate);
273
274 /**
275 * Get the SPI port number.
276 *
277 * @return The SPI port number.
278 */
279 int GetPort() const;
280
281 void InitSendable(wpi::SendableBuilder& builder) override;
282
283 private:
284 /** @brief ADIS16448 Register Map Declaration */
285 static constexpr uint8_t FLASH_CNT = 0x00; // Flash memory write count
286 static constexpr uint8_t XGYRO_OUT = 0x04; // X-axis gyroscope output
287 static constexpr uint8_t YGYRO_OUT = 0x06; // Y-axis gyroscope output
288 static constexpr uint8_t ZGYRO_OUT = 0x08; // Z-axis gyroscope output
289 static constexpr uint8_t XACCL_OUT = 0x0A; // X-axis accelerometer output
290 static constexpr uint8_t YACCL_OUT = 0x0C; // Y-axis accelerometer output
291 static constexpr uint8_t ZACCL_OUT = 0x0E; // Z-axis accelerometer output
292 static constexpr uint8_t XMAGN_OUT = 0x10; // X-axis magnetometer output
293 static constexpr uint8_t YMAGN_OUT = 0x12; // Y-axis magnetometer output
294 static constexpr uint8_t ZMAGN_OUT = 0x14; // Z-axis magnetometer output
295 static constexpr uint8_t BARO_OUT =
296 0x16; // Barometer pressure measurement, high word
297 static constexpr uint8_t TEMP_OUT = 0x18; // Temperature output
298 static constexpr uint8_t XGYRO_OFF =
299 0x1A; // X-axis gyroscope bias offset factor
300 static constexpr uint8_t YGYRO_OFF =
301 0x1C; // Y-axis gyroscope bias offset factor
302 static constexpr uint8_t ZGYRO_OFF =
303 0x1E; // Z-axis gyroscope bias offset factor
304 static constexpr uint8_t XACCL_OFF =
305 0x20; // X-axis acceleration bias offset factor
306 static constexpr uint8_t YACCL_OFF =
307 0x22; // Y-axis acceleration bias offset factor
308 static constexpr uint8_t ZACCL_OFF =
309 0x24; // Z-axis acceleration bias offset factor
310 static constexpr uint8_t XMAGN_HIC =
311 0x26; // X-axis magnetometer, hard iron factor
312 static constexpr uint8_t YMAGN_HIC =
313 0x28; // Y-axis magnetometer, hard iron factor
314 static constexpr uint8_t ZMAGN_HIC =
315 0x2A; // Z-axis magnetometer, hard iron factor
316 static constexpr uint8_t XMAGN_SIC =
317 0x2C; // X-axis magnetometer, soft iron factor
318 static constexpr uint8_t YMAGN_SIC =
319 0x2E; // Y-axis magnetometer, soft iron factor
320 static constexpr uint8_t ZMAGN_SIC =
321 0x30; // Z-axis magnetometer, soft iron factor
322 static constexpr uint8_t GPIO_CTRL = 0x32; // GPIO control
323 static constexpr uint8_t MSC_CTRL = 0x34; // MISC control
324 static constexpr uint8_t SMPL_PRD =
325 0x36; // Sample clock/Decimation filter control
326 static constexpr uint8_t SENS_AVG = 0x38; // Digital filter control
327 static constexpr uint8_t SEQ_CNT = 0x3A; // MAGN_OUT and BARO_OUT counter
328 static constexpr uint8_t DIAG_STAT = 0x3C; // System status
329 static constexpr uint8_t GLOB_CMD = 0x3E; // System command
330 static constexpr uint8_t ALM_MAG1 = 0x40; // Alarm 1 amplitude threshold
331 static constexpr uint8_t ALM_MAG2 = 0x42; // Alarm 2 amplitude threshold
332 static constexpr uint8_t ALM_SMPL1 = 0x44; // Alarm 1 sample size
333 static constexpr uint8_t ALM_SMPL2 = 0x46; // Alarm 2 sample size
334 static constexpr uint8_t ALM_CTRL = 0x48; // Alarm control
335 static constexpr uint8_t LOT_ID1 = 0x52; // Lot identification number
336 static constexpr uint8_t LOT_ID2 = 0x54; // Lot identification number
337 static constexpr uint8_t PROD_ID = 0x56; // Product identifier
338 static constexpr uint8_t SERIAL_NUM = 0x58; // Lot-specific serial number
339
340 /** @brief ADIS16448 Static Constants */
341 static constexpr double rad_to_deg = 57.2957795;
342 static constexpr double deg_to_rad = 0.0174532;
343 static constexpr double grav = 9.81;
344
345 /** @brief struct to store offset data */
346 struct OffsetData {
347 double gyro_rate_x = 0.0;
348 double gyro_rate_y = 0.0;
349 double gyro_rate_z = 0.0;
350 };
351
352 /** @brief Internal Resources **/
353 DigitalInput* m_reset_in = nullptr;
354 DigitalOutput* m_status_led = nullptr;
355
356 bool SwitchToStandardSPI();
357
358 bool SwitchToAutoSPI();
359
360 uint16_t ReadRegister(uint8_t reg);
361
362 void WriteRegister(uint8_t reg, uint16_t val);
363
364 void Acquire();
365
366 void Close();
367
368 // User-specified yaw axis
369 IMUAxis m_yaw_axis;
370
371 // Last read values (post-scaling)
372 double m_gyro_rate_x = 0.0;
373 double m_gyro_rate_y = 0.0;
374 double m_gyro_rate_z = 0.0;
375 double m_accel_x = 0.0;
376 double m_accel_y = 0.0;
377 double m_accel_z = 0.0;
378 double m_mag_x = 0.0;
379 double m_mag_y = 0.0;
380 double m_mag_z = 0.0;
381 double m_baro = 0.0;
382 double m_temp = 0.0;
383
384 // Complementary filter variables
385 double m_tau = 0.5;
386 double m_dt, m_alpha = 0.0;
387 double m_compAngleX, m_compAngleY, m_accelAngleX, m_accelAngleY = 0.0;
388
389 // vector for storing most recent imu values
390 OffsetData* m_offset_buffer = nullptr;
391
392 double m_gyro_rate_offset_x = 0.0;
393 double m_gyro_rate_offset_y = 0.0;
394 double m_gyro_rate_offset_z = 0.0;
395
396 // function to re-init offset buffer
397 void InitOffsetBuffer(int size);
398
399 // Accumulated gyro values (for offset calculation)
400 int m_avg_size = 0;
401 int m_accum_count = 0;
402
403 // Integrated gyro values
404 double m_integ_gyro_angle_x = 0.0;
405 double m_integ_gyro_angle_y = 0.0;
406 double m_integ_gyro_angle_z = 0.0;
407
408 // Complementary filter functions
409 double FormatFastConverge(double compAngle, double accAngle);
410
411 double FormatRange0to2PI(double compAngle);
412
413 double FormatAccelRange(double accelAngle, double accelZ);
414
415 double CompFilterProcess(double compAngle, double accelAngle, double omega);
416
417 // State and resource variables
418 std::atomic<bool> m_thread_active = false;
419 std::atomic<bool> m_first_run = true;
420 std::atomic<bool> m_thread_idle = false;
421 std::atomic<bool> m_start_up_mode = true;
422
423 bool m_auto_configured = false;
424 SPI::Port m_spi_port;
425 CalibrationTime m_calibration_time{0};
426 SPI* m_spi = nullptr;
427 DigitalInput* m_auto_interrupt = nullptr;
428 bool m_connected{false};
429
430 std::thread m_acquire_task;
431
432 hal::SimDevice m_simDevice;
433 hal::SimBoolean m_simConnected;
434 hal::SimDouble m_simGyroAngleX;
435 hal::SimDouble m_simGyroAngleY;
436 hal::SimDouble m_simGyroAngleZ;
437 hal::SimDouble m_simGyroRateX;
438 hal::SimDouble m_simGyroRateY;
439 hal::SimDouble m_simGyroRateZ;
440 hal::SimDouble m_simAccelX;
441 hal::SimDouble m_simAccelY;
442 hal::SimDouble m_simAccelZ;
443
444 struct NonMovableMutexWrapper {
445 wpi::mutex mutex;
446 NonMovableMutexWrapper() = default;
447
448 NonMovableMutexWrapper(const NonMovableMutexWrapper&) = delete;
449 NonMovableMutexWrapper& operator=(const NonMovableMutexWrapper&) = delete;
450
451 NonMovableMutexWrapper(NonMovableMutexWrapper&&) {}
452 NonMovableMutexWrapper& operator=(NonMovableMutexWrapper&&) {
453 return *this;
454 }
455
456 void lock() { mutex.lock(); }
457
458 void unlock() { mutex.unlock(); }
459
460 bool try_lock() noexcept { return mutex.try_lock(); }
461 };
462
463 mutable NonMovableMutexWrapper m_mutex;
464
465 // CRC-16 Look-Up Table
466 static constexpr uint16_t adiscrc[256] = {
467 0x0000, 0x17CE, 0x0FDF, 0x1811, 0x1FBE, 0x0870, 0x1061, 0x07AF, 0x1F3F,
468 0x08F1, 0x10E0, 0x072E, 0x0081, 0x174F, 0x0F5E, 0x1890, 0x1E3D, 0x09F3,
469 0x11E2, 0x062C, 0x0183, 0x164D, 0x0E5C, 0x1992, 0x0102, 0x16CC, 0x0EDD,
470 0x1913, 0x1EBC, 0x0972, 0x1163, 0x06AD, 0x1C39, 0x0BF7, 0x13E6, 0x0428,
471 0x0387, 0x1449, 0x0C58, 0x1B96, 0x0306, 0x14C8, 0x0CD9, 0x1B17, 0x1CB8,
472 0x0B76, 0x1367, 0x04A9, 0x0204, 0x15CA, 0x0DDB, 0x1A15, 0x1DBA, 0x0A74,
473 0x1265, 0x05AB, 0x1D3B, 0x0AF5, 0x12E4, 0x052A, 0x0285, 0x154B, 0x0D5A,
474 0x1A94, 0x1831, 0x0FFF, 0x17EE, 0x0020, 0x078F, 0x1041, 0x0850, 0x1F9E,
475 0x070E, 0x10C0, 0x08D1, 0x1F1F, 0x18B0, 0x0F7E, 0x176F, 0x00A1, 0x060C,
476 0x11C2, 0x09D3, 0x1E1D, 0x19B2, 0x0E7C, 0x166D, 0x01A3, 0x1933, 0x0EFD,
477 0x16EC, 0x0122, 0x068D, 0x1143, 0x0952, 0x1E9C, 0x0408, 0x13C6, 0x0BD7,
478 0x1C19, 0x1BB6, 0x0C78, 0x1469, 0x03A7, 0x1B37, 0x0CF9, 0x14E8, 0x0326,
479 0x0489, 0x1347, 0x0B56, 0x1C98, 0x1A35, 0x0DFB, 0x15EA, 0x0224, 0x058B,
480 0x1245, 0x0A54, 0x1D9A, 0x050A, 0x12C4, 0x0AD5, 0x1D1B, 0x1AB4, 0x0D7A,
481 0x156B, 0x02A5, 0x1021, 0x07EF, 0x1FFE, 0x0830, 0x0F9F, 0x1851, 0x0040,
482 0x178E, 0x0F1E, 0x18D0, 0x00C1, 0x170F, 0x10A0, 0x076E, 0x1F7F, 0x08B1,
483 0x0E1C, 0x19D2, 0x01C3, 0x160D, 0x11A2, 0x066C, 0x1E7D, 0x09B3, 0x1123,
484 0x06ED, 0x1EFC, 0x0932, 0x0E9D, 0x1953, 0x0142, 0x168C, 0x0C18, 0x1BD6,
485 0x03C7, 0x1409, 0x13A6, 0x0468, 0x1C79, 0x0BB7, 0x1327, 0x04E9, 0x1CF8,
486 0x0B36, 0x0C99, 0x1B57, 0x0346, 0x1488, 0x1225, 0x05EB, 0x1DFA, 0x0A34,
487 0x0D9B, 0x1A55, 0x0244, 0x158A, 0x0D1A, 0x1AD4, 0x02C5, 0x150B, 0x12A4,
488 0x056A, 0x1D7B, 0x0AB5, 0x0810, 0x1FDE, 0x07CF, 0x1001, 0x17AE, 0x0060,
489 0x1871, 0x0FBF, 0x172F, 0x00E1, 0x18F0, 0x0F3E, 0x0891, 0x1F5F, 0x074E,
490 0x1080, 0x162D, 0x01E3, 0x19F2, 0x0E3C, 0x0993, 0x1E5D, 0x064C, 0x1182,
491 0x0912, 0x1EDC, 0x06CD, 0x1103, 0x16AC, 0x0162, 0x1973, 0x0EBD, 0x1429,
492 0x03E7, 0x1BF6, 0x0C38, 0x0B97, 0x1C59, 0x0448, 0x1386, 0x0B16, 0x1CD8,
493 0x04C9, 0x1307, 0x14A8, 0x0366, 0x1B77, 0x0CB9, 0x0A14, 0x1DDA, 0x05CB,
494 0x1205, 0x15AA, 0x0264, 0x1A75, 0x0DBB, 0x152B, 0x02E5, 0x1AF4, 0x0D3A,
495 0x0A95, 0x1D5B, 0x054A, 0x1284};
496};
497
498} // namespace frc
Use DMA SPI to read rate, acceleration, and magnetometer data from the ADIS16448 IMU and return the r...
Definition: ADIS16448_IMU.h:55
int ConfigDecRate(uint16_t decimationRate)
Configures the decimation rate of the IMU.
units::tesla_t GetMagneticFieldZ() const
Returns the magnetic field strength in the Z axis.
units::meters_per_second_squared_t GetAccelZ() const
Returns the acceleration in the Z axis.
units::degree_t GetYFilteredAccelAngle() const
Returns the Y-axis filtered acceleration angle.
units::degree_t GetGyroAngleX() const
Returns the accumulated gyro angle in the X axis.
units::degree_t GetXFilteredAccelAngle() const
Returns the X-axis filtered acceleration angle.
units::degree_t GetYComplementaryAngle() const
Returns the complementary angle around the Y axis computed from accelerometer and gyro rate measureme...
units::celsius_t GetTemperature() const
Returns the temperature.
units::degree_t GetAngle() const
Returns the yaw axis angle in degrees (CCW positive).
units::tesla_t GetMagneticFieldY() const
Returns the magnetic field strength in the Y axis.
units::degree_t GetXComplementaryAngle() const
Returns the complementary angle around the X axis computed from accelerometer and gyro rate measureme...
int SetYawAxis(IMUAxis yaw_axis)
int ConfigCalTime(CalibrationTime new_cal_time)
Configures the calibration time used for the next calibrate.
ADIS16448_IMU(IMUAxis yaw_axis, SPI::Port port, CalibrationTime cal_time)
IMU constructor on the specified MXP port and orientation.
IMUAxis
IMU axes.
Definition: ADIS16448_IMU.h:90
@ kY
The IMU's Y axis.
Definition: ADIS16448_IMU.h:94
@ kX
The IMU's X axis.
Definition: ADIS16448_IMU.h:92
@ kZ
The IMU's Z axis.
Definition: ADIS16448_IMU.h:96
void Reset()
Reset the gyro.
CalibrationTime
ADIS16448 calibration times.
Definition: ADIS16448_IMU.h:60
units::pounds_per_square_inch_t GetBarometricPressure() const
Returns the barometric pressure.
ADIS16448_IMU & operator=(ADIS16448_IMU &&)
void Calibrate()
Initialize the IMU.
units::degrees_per_second_t GetGyroRateX() const
Returns the angular rate in the X axis.
~ADIS16448_IMU() override
units::degrees_per_second_t GetGyroRateY() const
Returns the angular rate in the Y axis.
units::degrees_per_second_t GetRate() const
Returns the yaw axis angular rate in degrees per second (CCW positive).
units::meters_per_second_squared_t GetAccelY() const
Returns the acceleration in the Y axis.
int GetPort() const
Get the SPI port number.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
units::degree_t GetGyroAngleY() const
Returns the accumulated gyro angle in the Y axis.
units::degree_t GetGyroAngleZ() const
Returns the accumulated gyro angle in the Z axis.
units::meters_per_second_squared_t GetAccelX() const
Returns the acceleration in the X axis.
IMUAxis GetYawAxis() const
ADIS16448_IMU(ADIS16448_IMU &&)
bool IsConnected() const
Checks the connection status of the IMU.
ADIS16448_IMU()
IMU constructor on onboard MXP CS0, Z-up orientation, and complementary AHRS computation.
units::tesla_t GetMagneticFieldX() const
Returns the magnetic field strength in the X axis.
units::degrees_per_second_t GetGyroRateZ() const
Returns the angular rate in the Z axis.
Class to read a digital input.
Definition: DigitalInput.h:27
Class to write to digital outputs.
Definition: DigitalOutput.h:25
Port
SPI port.
Definition: SPI.h:31
C++ wrapper around a HAL simulator boolean value handle.
Definition: SimDevice.h:608
A move-only C++ wrapper around a HAL simulator device handle.
Definition: SimDevice.h:642
C++ wrapper around a HAL simulator double value handle.
Definition: SimDevice.h:533
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15
::std::mutex mutex
Definition: mutex.h:17